Module collision_objects

Provides classes/functions for loading objects into the simulation environment.

class trifinger_simulation.collision_objects.ColoredCubeV2(position=(0, 0, 0), orientation=(0, 0, 0, 1), pybullet_client_id=0)[source]

Model of the colored “Cube v2”.

Parameters:
  • position (Sequence[float]) – Position at which the cube is spawned.

  • orientation (Sequence[float]) – Orientation with which the cube is spawned.

  • pybullet_client_id (int) – Optional ID of the pybullet client.

get_state()
Returns:

Current position and orientation of the object.

Return type:

Tuple[List[float], List[float]]

set_state(position, orientation)

Resets the object to the provided position and orientation

Parameters:
  • position (Sequence[float]) – New position.

  • orientation (Sequence[float]) – New orientation (quaternion).

class trifinger_simulation.collision_objects.Cube(position=[0.15, 0.0, 0.0425], orientation=[0, 0, 0, 1], half_width=0.0325, mass=0.08, color_rgba=None, pybullet_client_id=0)[source]

A cube object.

Parameters:
  • position (Sequence[float]) – Initial xyz-position of the cuboid.

  • orientation (Sequence[float]) – Initial orientation quaternion (x, y, z, w) of the cuboid.

  • half_extents – Half-extends of the cuboid in x/y/z-direction.

  • mass (float) – Mass of the cuboid in kg. Set to 0 for a static object.

  • color_rgba (Sequence[float] | None) – Optional tuple of RGBA colour.

  • pybullet_client_id (int) – Optional ID of the pybullet client.

  • half_width (float)

get_state()
Returns:

Current position and orientation of the object.

Return type:

Tuple[List[float], List[float]]

set_state(position, orientation)

Resets the object to the provided position and orientation

Parameters:
  • position (Sequence[float]) – New position.

  • orientation (Sequence[float]) – New orientation (quaternion).

class trifinger_simulation.collision_objects.Cuboid(position, orientation, half_extents, mass, color_rgba=None, pybullet_client_id=0)[source]

A cuboid which can be interacted with.

Parameters:
  • position (Sequence[float]) – Initial xyz-position of the cuboid.

  • orientation (Sequence[float]) – Initial orientation quaternion (x, y, z, w) of the cuboid.

  • half_extents (Sequence[float]) – Half-extends of the cuboid in x/y/z-direction.

  • mass (float) – Mass of the cuboid in kg. Set to 0 for a static object.

  • color_rgba (Sequence[float] | None) – Optional tuple of RGBA colour.

  • pybullet_client_id (int) – Optional ID of the pybullet client.

get_state()
Returns:

Current position and orientation of the object.

Return type:

Tuple[List[float], List[float]]

set_state(position, orientation)

Resets the object to the provided position and orientation

Parameters:
  • position (Sequence[float]) – New position.

  • orientation (Sequence[float]) – New orientation (quaternion).

trifinger_simulation.collision_objects.import_mesh(mesh_file_path, position, orientation=[0, 0, 0, 1], is_concave=False, color_rgba=None, pybullet_client_id=0)[source]

Create a collision object based on a mesh file.

Parameters:
  • mesh_file_path (str) – Path to the mesh file.

  • position (Sequence[float]) – Position (x, y, z) of the object.

  • orientation (Sequence[float]) – Quaternion defining the orientation of the object.

  • is_concave (bool) – If set to true, the object is loaded as concav shape. Only use this for static objects.

  • color_rgba (Sequence[float] | None) – Optional colour of the object given as a list of RGBA values in the interval [0, 1]. If not specified, pyBullet assigns a random colour.

  • pybullet_client_id (int)

Returns:

ID of the created object.

Return type:

int