PyBullet Class

class panda_gym.pybullet.PyBullet(render: bool = False, n_substeps: int = 20, background_color: Optional[ndarray] = None)

Convenient class to use PyBullet physics engine.

Parameters
  • render (bool, optional) – Enable rendering. Defaults to False.

  • n_substeps (int, optional) – Number of sim substep when step() is called. Defaults to 20.

  • background_color (np.ndarray, optional) – The background color as (red, green, blue). Defaults to np.array([223, 54, 45]).

close() None

Close the simulation.

control_joints(body: str, joints: ndarray, target_angles: ndarray, forces: ndarray) None

Control the joints motor.

Parameters
  • body (str) – Body unique name.

  • joints (np.ndarray) – List of joint indices, as a list of ints.

  • target_angles (np.ndarray) – List of target angles, as a list of floats.

  • forces (np.ndarray) – Forces to apply, as a list of floats.

create_box(body_name: str, half_extents: ndarray, mass: float, position: ndarray, rgba_color: Optional[ndarray] = None, specular_color: Optional[ndarray] = None, ghost: bool = False, lateral_friction: Optional[float] = None, spinning_friction: Optional[float] = None, texture: Optional[str] = None) None

Create a box.

Parameters
  • body_name (str) – The name of the body. Must be unique in the sim.

  • half_extents (np.ndarray) – Half size of the box in meters, as (x, y, z).

  • mass (float) – The mass in kg.

  • position (np.ndarray) – The position, as (x, y, z).

  • rgba_color (np.ndarray, optional) – Body color, as (r, g, b, a). Defaults as [0, 0, 0, 0]

  • specular_color (np.ndarray, optional) – Specular color, as (r, g, b). Defaults to [0, 0, 0].

  • ghost (bool, optional) – Whether the body can collide. Defaults to False.

  • lateral_friction (float or None, optional) – Lateral friction. If None, use the default pybullet value. Defaults to None.

  • spinning_friction (float or None, optional) – Spinning friction. If None, use the default pybullet value. Defaults to None.

  • texture (str or None, optional) – Texture file name. Defaults to None.

create_cylinder(body_name: str, radius: float, height: float, mass: float, position: ndarray, rgba_color: Optional[ndarray] = None, specular_color: Optional[ndarray] = None, ghost: bool = False, lateral_friction: Optional[float] = None, spinning_friction: Optional[float] = None) None

Create a cylinder.

Parameters
  • body_name (str) – The name of the body. Must be unique in the sim.

  • radius (float) – The radius in meter.

  • height (float) – The height in meter.

  • mass (float) – The mass in kg.

  • position (np.ndarray) – The position, as (x, y, z).

  • rgba_color (np.ndarray, optional) – Body color, as (r, g, b, a). Defaults as [0, 0, 0, 0]

  • specular_color (np.ndarray, optional) – Specular color, as (r, g, b). Defaults to [0, 0, 0].

  • ghost (bool, optional) – Whether the body can collide. Defaults to False.

  • lateral_friction (float or None, optional) – Lateral friction. If None, use the default pybullet value. Defaults to None.

  • spinning_friction (float or None, optional) – Spinning friction. If None, use the default pybullet value. Defaults to None.

create_plane(z_offset: float) None

Create a plane. (Actually, it is a thin box.)

Parameters

z_offset (float) – Offset of the plane.

create_sphere(body_name: str, radius: float, mass: float, position: ndarray, rgba_color: Optional[ndarray] = None, specular_color: Optional[ndarray] = None, ghost: bool = False, lateral_friction: Optional[float] = None, spinning_friction: Optional[float] = None) None

Create a sphere.

Parameters
  • body_name (str) – The name of the body. Must be unique in the sim.

  • radius (float) – The radius in meter.

  • mass (float) – The mass in kg.

  • position (np.ndarray) – The position, as (x, y, z).

  • rgba_color (np.ndarray, optional) – Body color, as (r, g, b, a). Defaults as [0, 0, 0, 0]

  • specular_color (np.ndarray, optional) – Specular color, as (r, g, b). Defaults to [0, 0, 0].

  • ghost (bool, optional) – Whether the body can collide. Defaults to False.

  • lateral_friction (float or None, optional) – Lateral friction. If None, use the default pybullet value. Defaults to None.

  • spinning_friction (float or None, optional) – Spinning friction. If None, use the default pybullet value. Defaults to None.

create_table(length: float, width: float, height: float, x_offset: float = 0.0, lateral_friction: Optional[float] = None, spinning_friction: Optional[float] = None) None

Create a fixed table. Top is z=0, centered in y.

Parameters
  • length (float) – The length of the table (x direction).

  • width (float) – The width of the table (y direction)

  • height (float) – The height of the table.

  • x_offset (float, optional) – The offet in the x direction.

  • lateral_friction (float or None, optional) – Lateral friction. If None, use the default pybullet value. Defaults to None.

  • spinning_friction (float or None, optional) – Spinning friction. If None, use the default pybullet value. Defaults to None.

property dt

Timestep.

get_base_angular_velocity(body: str) ndarray

Get the angular velocity of the body.

Parameters

body (str) – Body unique name.

Returns

The angular velocity, as (wx, wy, wz).

Return type

np.ndarray

get_base_orientation(body: str) ndarray

Get the orientation of the body.

Parameters

body (str) – Body unique name.

Returns

The orientation, as quaternion (x, y, z, w).

Return type

np.ndarray

get_base_position(body: str) ndarray

Get the position of the body.

Parameters

body (str) – Body unique name.

Returns

The position, as (x, y, z).

Return type

np.ndarray

get_base_rotation(body: str, type: str = 'euler') ndarray

Get the rotation of the body.

Parameters
  • body (str) – Body unique name.

  • type (str) – Type of angle, either “euler” or “quaternion”

Returns

The rotation.

Return type

np.ndarray

get_base_velocity(body: str) ndarray

Get the velocity of the body.

Parameters

body (str) – Body unique name.

Returns

The velocity, as (vx, vy, vz).

Return type

np.ndarray

get_joint_angle(body: str, joint: int) float

Get the angle of the joint of the body.

Parameters
  • body (str) – Body unique name.

  • joint (int) – Joint index in the body

Returns

The angle.

Return type

float

get_joint_velocity(body: str, joint: int) float

Get the velocity of the joint of the body.

Parameters
  • body (str) – Body unique name.

  • joint (int) – Joint index in the body

Returns

The velocity.

Return type

float

Get the angular velocity of the link of the body.

Parameters
  • body (str) – Body unique name.

  • link (int) – Link index in the body.

Returns

The angular velocity, as (wx, wy, wz).

Return type

np.ndarray

Get the orientation of the link of the body.

Parameters
  • body (str) – Body unique name.

  • link (int) – Link index in the body.

Returns

The rotation, as (rx, ry, rz).

Return type

np.ndarray

Get the position of the link of the body.

Parameters
  • body (str) – Body unique name.

  • link (int) – Link index in the body.

Returns

The position, as (x, y, z).

Return type

np.ndarray

Get the velocity of the link of the body.

Parameters
  • body (str) – Body unique name.

  • link (int) – Link index in the body.

Returns

The velocity, as (vx, vy, vz).

Return type

np.ndarray

inverse_kinematics(body: str, link: int, position: ndarray, orientation: ndarray) ndarray

Compute the inverse kinematics and return the new joint state.

Parameters
  • body (str) – Body unique name.

  • link (int) – Link index in the body.

  • position (np.ndarray) – Desired position of the end-effector, as (x, y, z).

  • orientation (np.ndarray) – Desired orientation of the end-effector as quaternion (x, y, z, w).

Returns

The new joint state.

Return type

np.ndarray

loadURDF(body_name: str, **kwargs: Any) None

Load URDF file.

Parameters

body_name (str) – The name of the body. Must be unique in the sim.

no_rendering() Iterator[None]

Disable rendering within this context.

place_visualizer(target_position: ndarray, distance: float, yaw: float, pitch: float) None

Orient the camera used for rendering.

Parameters
  • target (np.ndarray) – Target position, as (x, y, z).

  • distance (float) – Distance from the target position.

  • yaw (float) – Yaw.

  • pitch (float) – Pitch.

remove_state(state_id: int) None

Remove a simulation state. This will make this state_id available again for returning in save_state().

Parameters

state_id – The simulation state id returned by save_state().

render(mode: str = 'human', width: int = 720, height: int = 480, target_position: Optional[ndarray] = None, distance: float = 1.4, yaw: float = 45, pitch: float = - 30, roll: float = 0) Optional[ndarray]

Render.

If mode is “human”, make the rendering real-time. All other arguments are unused. If mode is “rgb_array”, return an RGB array of the scene.

Parameters
  • mode (str) – “human” of “rgb_array”. If “human”, this method waits for the time necessary to have a realistic temporal rendering and all other args are ignored. Else, return an RGB array.

  • width (int, optional) – Image width. Defaults to 720.

  • height (int, optional) – Image height. Defaults to 480.

  • target_position (np.ndarray, optional) – Camera targetting this postion, as (x, y, z). Defaults to [0., 0., 0.].

  • distance (float, optional) – Distance of the camera. Defaults to 1.4.

  • yaw (float, optional) – Yaw of the camera. Defaults to 45.

  • pitch (float, optional) – Pitch of the camera. Defaults to -30.

  • roll (int, optional) – Rool of the camera. Defaults to 0.

Returns

An RGB array if mode is ‘rgb_array’, else None.

Return type

RGB np.ndarray or None

restore_state(state_id: int) None

Restore a simulation state.

Parameters

state_id – The simulation state id returned by save_state().

save_state() int

Save the current simulation state.

Returns

A state id assigned by PyBullet, which is the first non-negative integer available for indexing.

Return type

int

set_base_pose(body: str, position: ndarray, orientation: ndarray) None

Set the position of the body.

Parameters
  • body (str) – Body unique name.

  • position (np.ndarray) – The position, as (x, y, z).

  • orientation (np.ndarray) – The target orientation as quaternion (x, y, z, w).

set_joint_angle(body: str, joint: int, angle: float) None

Set the angle of the joint of the body.

Parameters
  • body (str) – Body unique name.

  • joint (int) – Joint index in the body.

  • angle (float) – Target angle.

set_joint_angles(body: str, joints: ndarray, angles: ndarray) None

Set the angles of the joints of the body.

Parameters
  • body (str) – Body unique name.

  • joints (np.ndarray) – List of joint indices, as a list of ints.

  • angles (np.ndarray) – List of target angles, as a list of floats.

set_lateral_friction(body: str, link: int, lateral_friction: float) None

Set the lateral friction of a link.

Parameters
  • body (str) – Body unique name.

  • link (int) – Link index in the body.

  • lateral_friction (float) – Lateral friction.

set_spinning_friction(body: str, link: int, spinning_friction: float) None

Set the spinning friction of a link.

Parameters
  • body (str) – Body unique name.

  • link (int) – Link index in the body.

  • spinning_friction (float) – Spinning friction.

step() None

Step the simulation.