pycram.worlds.bullet_world

Module Contents

Classes

BulletWorld

This class represents a BulletWorld, which is a simulation environment that uses the Bullet Physics Engine. This

Gui

For internal use only. Creates a new thread for the physics simulation that is active until closed by

Attributes

Link

RootLink

Joint

pycram.worlds.bullet_world.Joint
class pycram.worlds.bullet_world.BulletWorld(mode: pycram.datastructures.enums.WorldMode = WorldMode.DIRECT, is_prospection_world: bool = False, sim_frequency=240)

Bases: pycram.world.World

This class represents a BulletWorld, which is a simulation environment that uses the Bullet Physics Engine. This class is the main interface to the Bullet Physics Engine and should be used to spawn Objects, simulate Physic and manipulate the Bullet World.

Creates a new simulation, the type decides of the simulation should be a rendered window or just run in the background. There can only be one rendered simulation. The BulletWorld object also initializes the Events for attachment, detachment and for manipulating the world.

Parameters:
  • mode – Can either be “GUI” for rendered window or “DIRECT” for non-rendered. The default is “GUI”

  • is_prospection_world – For internal usage, decides if this BulletWorld should be used as a shadow world.

extension: str
get_object_number_of_joints
_init_world(mode: pycram.datastructures.enums.WorldMode)

Initializes the physics simulation.

load_object_and_get_id(path: typing_extensions.Optional[str] = None, pose: typing_extensions.Optional[pycram.datastructures.pose.Pose] = None) int

Loads a description file (e.g. URDF) at the given pose and returns the id of the loaded object.

Parameters:
  • path – The path to the description file, if None the description file is assumed to be already loaded.

  • pose – The pose at which the object should be loaded.

Returns:

The id of the loaded object.

_load_object_and_get_id(path: str, pose: pycram.datastructures.pose.Pose) int
remove_object_from_simulator(obj: pycram.world_concepts.world_object.Object) None

Removes an object from the physics simulator.

Parameters:

obj – The object to be removed.

add_constraint(constraint: pycram.world_concepts.constraints.Constraint) int

Add a constraint between two objects links so that they become attached for example.

Parameters:

constraint – The constraint data used to create the constraint.

remove_constraint(constraint_id)

Remove a constraint by its ID.

Parameters:

constraint_id – The unique id of the constraint to be removed.

get_joint_position(joint: pycram.object_descriptors.urdf.ObjectDescription.Joint) float

Get the position of a joint of an articulated object

Parameters:

joint – The joint to get the position for.

Returns:

The joint position as a float.

get_object_joint_names(obj: pycram.world_concepts.world_object.Object) typing_extensions.List[str]

Returns the names of all joints of this object.

Parameters:

obj – The object.

Returns:

A list of joint names.

Get the pose of a link of an articulated object with respect to the world frame.

Parameters:

link – The link as a AbstractLink object.

Returns:

The pose of the link as a Pose object.

Returns the names of all links of this object.

Parameters:

obj – The object.

Returns:

A list of link names.

perform_collision_detection() None

Checks for collisions between all objects in the World and updates the contact points.

get_object_contact_points(obj: pycram.world_concepts.world_object.Object) typing_extensions.List
For a more detailed explanation of the

returned list please look at: PyBullet Doc

get_contact_points_between_two_objects(obj1: pycram.world_concepts.world_object.Object, obj2: pycram.world_concepts.world_object.Object) typing_extensions.List

Returns a list of contact points between obj1 and obj2.

Parameters:
  • obj1 – The first object.

  • obj2 – The second object.

Returns:

A list of all contact points between the two objects.

reset_joint_position(joint: pycram.object_descriptors.urdf.ObjectDescription.Joint, joint_position: str) None

Reset the joint position instantly without physics simulation

Parameters:
  • joint – The joint to reset the position for.

  • joint_position – The new joint pose.

reset_object_base_pose(obj: pycram.world_concepts.world_object.Object, pose: pycram.datastructures.pose.Pose) None

Reset the world position and orientation of the base of the object instantaneously, not through physics simulation. (x,y,z) position vector and (x,y,z,w) quaternion orientation.

Parameters:
  • obj – The object.

  • pose – The new pose as a Pose object.

step()

Step the world simulation using forward dynamics

get_object_pose(obj: pycram.world_concepts.world_object.Object) pycram.datastructures.pose.Pose

Get the pose of an object in the world frame from the current object pose in the simulator.

Changes the rgba_color of a link of this object, the rgba_color has to be given as Color object.

Parameters:
  • link – The link which should be colored.

  • rgba_color – The rgba_color as Color object with RGBA values between 0 and 1.

This method returns the rgba_color of this link.

Parameters:

link – The link for which the rgba_color should be returned.

Returns:

The rgba_color as Color object with RGBA values between 0 and 1.

Get the RGBA colors of each link in the object as a dictionary from link name to rgba_color.

Parameters:

obj – The object

Returns:

A dictionary with link names as keys and a Color object for each link as value.

get_object_axis_aligned_bounding_box(obj: pycram.world_concepts.world_object.Object) pycram.datastructures.dataclasses.AxisAlignedBoundingBox

Returns the axis aligned bounding box of this object. The return of this method are two points in world coordinate frame which define a bounding box.

Parameters:

obj – The object for which the bounding box should be returned.

Returns:

AxisAlignedBoundingBox object containing the min and max points of the bounding box.

Returns the axis aligned bounding box of the link. The return of this method are two points in world coordinate frame which define a bounding box.

set_realtime(real_time: bool) None

Enables the real time simulation of Physics in the World. By default, this is disabled and Physics is only simulated to reason about it.

Parameters:

real_time – Whether the World should simulate Physics in real time.

set_gravity(gravity_vector: typing_extensions.List[float]) None
Sets the gravity that is used in the World. By default, it is set to the gravity on earth ([0, 0, -9.8]).

Gravity is given as a vector in x,y,z. Gravity is only applied while simulating Physic.

Parameters:

gravity_vector – The gravity vector that should be used in the World.

disconnect_from_physics_server()

Disconnects the world from the physics server.

join_threads()

Joins the GUI thread if it exists.

join_gui_thread_if_exists()
save_physics_simulator_state() int

Saves the state of the physics simulator and returns the unique id of the state.

Returns:

The unique id representing the state.

restore_physics_simulator_state(state_id)
Restores the objects and environment state in the physics simulator according to

the given state using the unique state id.

Parameters:

state_id – The unique id representing the state.

remove_physics_simulator_state(state_id: int)

Removes the state of the physics simulator with the given id.

Parameters:

state_id – The unique id representing the state.

add_vis_axis(pose: pycram.datastructures.pose.Pose, length: typing_extensions.Optional[float] = 0.2) None

Creates a Visual object which represents the coordinate frame at the given position and orientation. There can be an unlimited amount of vis axis objects.

Parameters:
  • pose – The pose at which the axis should be spawned

  • length – Optional parameter to configure the length of the axes

remove_vis_axis() None

Removes all spawned vis axis objects that are currently in this BulletWorld.

ray_test(from_position: typing_extensions.List[float], to_position: typing_extensions.List[float]) int

Cast a ray and return the first object hit, if any.

Parameters:
  • from_position – The starting position of the ray in Cartesian world coordinates.

  • to_position – The ending position of the ray in Cartesian world coordinates.

Returns:

The object id of the first object hit, or -1 if no object was hit.

ray_test_batch(from_positions: typing_extensions.List[typing_extensions.List[float]], to_positions: typing_extensions.List[typing_extensions.List[float]], num_threads: int = 1) typing_extensions.List[int]
Cast a batch of rays and return the result for each of the rays (first object hit, if any. or -1)
Takes optional argument num_threads to specify the number of threads to use
to compute the ray intersections for the batch. Specify 0 to let simulator decide, 1 (default) for single

core execution, 2 or more to select the number of threads to use.

Parameters:
  • from_positions – The starting positions of the rays in Cartesian world coordinates.

  • to_positions – The ending positions of the rays in Cartesian world coordinates.

  • num_threads – The number of threads to use to compute the ray intersections for the batch.

create_visual_shape(visual_shape: pycram.datastructures.dataclasses.VisualShape) int

Creates a visual shape in the physics simulator and returns the unique id of the created shape.

Parameters:

visual_shape – The visual shape to be created, uses the VisualShape dataclass defined in world_dataclasses

Returns:

The unique id of the created shape.

create_multi_body(multi_body: pycram.datastructures.dataclasses.MultiBody) int

Creates a multi body in the physics simulator and returns the unique id of the created multi body. The multibody is created by joining multiple links/shapes together with joints.

Parameters:

multi_body – The multi body to be created, uses the MultiBody dataclass defined in world_dataclasses.

Returns:

The unique id of the created multi body.

get_images_for_target(target_pose: pycram.datastructures.pose.Pose, cam_pose: pycram.datastructures.pose.Pose, size: typing_extensions.Optional[int] = 256) typing_extensions.List[numpy.ndarray]

Calculates the view and projection Matrix and returns 3 images:

  1. An RGB image

  2. A depth image

  3. A segmentation Mask, the segmentation mask indicates for every pixel the visible Object

Parameters:
  • target_pose – The pose to which the camera should point.

  • cam_pose – The pose of the camera.

  • size – The height and width of the images in pixels.

Returns:

A list containing an RGB and depth image as well as a segmentation mask, in this order.

add_text(text: str, position: typing_extensions.List[float], orientation: typing_extensions.Optional[typing_extensions.List[float]] = None, size: typing_extensions.Optional[float] = None, color: typing_extensions.Optional[pycram.datastructures.dataclasses.Color] = Color(), life_time: typing_extensions.Optional[float] = 0, parent_object_id: typing_extensions.Optional[int] = None, parent_link_id: typing_extensions.Optional[int] = None) int

Adds text to the world.

Parameters:
  • text – The text to be added.

  • position – The position of the text in the world.

  • orientation – By default, debug text will always face the camera, automatically rotation. By specifying a text orientation (quaternion), the orientation will be fixed in world space or local space (when parent is specified).

  • size – The size of the text.

  • color – The color of the text.

  • life_time – The lifetime in seconds of the text to remain in the world, if 0 the text will remain in the world until it is removed manually.

  • parent_object_id – The id of the object to which the text should be attached.

  • parent_link_id – The id of the link to which the text should be attached.

Returns:

The id of the added text.

remove_text(text_id: typing_extensions.Optional[int] = None) None

Removes text from the world using the given id. if no id is given all text will be removed.

Parameters:

text_id – The id of the text to be removed.

enable_joint_force_torque_sensor(obj: pycram.world_concepts.world_object.Object, fts_joint_idx: int) None

You can enable a joint force/torque sensor in each joint. Once enabled, if you perform a simulation step, the get_joint_reaction_force_torque will report the joint reaction forces in the fixed degrees of freedom: a fixed joint will measure all 6DOF joint forces/torques. A revolute/hinge joint force/torque sensor will measure 5DOF reaction forces along all axis except the hinge axis. The applied force by a joint motor is available through get_applied_joint_motor_torque.

Parameters:
  • obj – The object in which the joint is located.

  • fts_joint_idx – The index of the joint for which the force torque sensor should be enabled.

disable_joint_force_torque_sensor(obj: pycram.world_concepts.world_object.Object, joint_id: int) None

Disables the force torque sensor of a joint.

Parameters:
  • obj – The object in which the joint is located.

  • joint_id – The id of the joint for which the force torque sensor should be disabled.

get_joint_reaction_force_torque(obj: pycram.world_concepts.world_object.Object, joint_id: int) typing_extensions.List[float]

Returns the joint reaction forces and torques of the specified joint.

Parameters:
  • obj – The object in which the joint is located.

  • joint_id – The id of the joint for which the force torque should be returned.

Returns:

The joint reaction forces and torques of the specified joint.

get_applied_joint_motor_torque(obj: pycram.world_concepts.world_object.Object, joint_id: int) float

Returns the applied torque by a joint motor.

Parameters:
  • obj – The object in which the joint is located.

  • joint_id – The id of the joint for which the applied motor torque should be returned.

Returns:

The applied torque by a joint motor.

class pycram.worlds.bullet_world.Gui(world: pycram.world.World, mode: pycram.datastructures.enums.WorldMode)

Bases: threading.Thread

For internal use only. Creates a new thread for the physics simulation that is active until closed by exit() Also contains the code for controlling the camera.

This constructor should always be called with keyword arguments. Arguments are:

group should be None; reserved for future extension when a ThreadGroup class is implemented.

target is the callable object to be invoked by the run() method. Defaults to None, meaning nothing is called.

name is the thread name. By default, a unique name is constructed of the form “Thread-N” where N is a small decimal number.

args is the argument tuple for the target invocation. Defaults to ().

kwargs is a dictionary of keyword arguments for the target invocation. Defaults to {}.

If a subclass overrides the constructor, it must make sure to invoke the base class constructor (Thread.__init__()) before doing anything else to the thread.

run()

Initializes the new simulation and checks in an endless loop if it is still active. If it is the thread will be suspended for 1/80 seconds, if it is not the method and thus the thread terminates. The loop also checks for mouse and keyboard inputs to control the camera.