pycram.worlds.bullet_world
==========================

.. py:module:: pycram.worlds.bullet_world


Attributes
----------

.. autoapisummary::

   pycram.worlds.bullet_world.Link
   pycram.worlds.bullet_world.RootLink
   pycram.worlds.bullet_world.Joint


Classes
-------

.. autoapisummary::

   pycram.worlds.bullet_world.BulletWorld
   pycram.worlds.bullet_world.Gui


Module Contents
---------------

.. py:data:: Link

.. py:data:: RootLink

.. py:data:: Joint

.. py:class:: BulletWorld(mode: pycram.datastructures.enums.WorldMode = WorldMode.DIRECT, is_prospection: bool = False, use_multiverse_for_real_world_simulation: bool = False)

   Bases: :py:obj:`pycram.datastructures.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.


   .. py:attribute:: vis_axis
      :type:  typing_extensions.List[int]
      :value: []



   .. py:method:: add_multiverse_resources()

      Add the Multiverse resources to the start of the data directories of the BulletWorld such they are searched
      first for the resources because the pycram objects need to have the same description as the Multiverse objects.



   .. py:method:: _init_world(mode: pycram.datastructures.enums.WorldMode)


   .. py:method:: load_generic_object_and_get_id(description: pycram.object_descriptors.generic.ObjectDescription, pose: typing_extensions.Optional[pycram.datastructures.pose.PoseStamped] = None) -> int

      Creates a visual and collision box in the simulation.



   .. py:method:: load_object_and_get_id(path: typing_extensions.Optional[str] = None, pose: typing_extensions.Optional[pycram.datastructures.pose.PoseStamped] = None, obj_type: typing_extensions.Optional[pycram.datastructures.enums.ObjectType] = None) -> int


   .. py:method:: _load_object_and_get_id(path: str, pose: pycram.datastructures.pose.PoseStamped) -> int


   .. py:method:: _remove_visual_object(obj_id: int) -> bool


   .. py:method:: remove_object_from_simulator(obj: pycram.world_concepts.world_object.Object) -> bool


   .. py:method:: _remove_body(body_id: int) -> typing_extensions.Any

      Remove a body from PyBullet using the body id.

      :param body_id: The id of the body.



   .. py:method:: add_constraint(constraint: pycram.world_concepts.constraints.Constraint) -> int


   .. py:method:: remove_constraint(constraint_id)


   .. py:method:: _get_joint_position(joint: pycram.object_descriptors.urdf.ObjectDescription.Joint) -> float


   .. py:method:: get_object_joint_names(obj: pycram.world_concepts.world_object.Object) -> typing_extensions.List[str]


   .. py:method:: get_multiple_link_poses(links: typing_extensions.List[Link]) -> typing_extensions.Dict[str, pycram.datastructures.pose.PoseStamped]


   .. py:method:: get_multiple_link_positions(links: typing_extensions.List[Link]) -> typing_extensions.Dict[str, typing_extensions.List[float]]


   .. py:method:: get_multiple_link_orientations(links: typing_extensions.List[Link]) -> typing_extensions.Dict[str, typing_extensions.List[float]]


   .. py:method:: get_link_position(link: Link) -> typing_extensions.List[float]


   .. py:method:: get_link_orientation(link: Link) -> typing_extensions.List[float]


   .. py:method:: get_link_pose(link: pycram.object_descriptors.urdf.ObjectDescription.Link) -> pycram.datastructures.pose.PoseStamped


   .. py:method:: get_object_link_names(obj: pycram.world_concepts.world_object.Object) -> typing_extensions.List[str]


   .. py:method:: get_object_number_of_links(obj: pycram.world_concepts.world_object.Object) -> int


   .. py:attribute:: get_object_number_of_joints


   .. py:method:: perform_collision_detection() -> None


   .. py:method:: get_body_contact_points(body: pycram.datastructures.world_entity.PhysicalBody) -> pycram.datastructures.dataclasses.ContactPointsList


   .. py:method:: get_contact_points_between_two_bodies(obj_a: pycram.datastructures.world_entity.PhysicalBody, obj_b: pycram.datastructures.world_entity.PhysicalBody) -> pycram.datastructures.dataclasses.ContactPointsList


   .. py:method:: get_body_closest_points(body: pycram.datastructures.world_entity.PhysicalBody, max_distance: float) -> pycram.datastructures.dataclasses.ClosestPointsList


   .. py:method:: get_closest_points_between_two_bodies(obj_a: pycram.datastructures.world_entity.PhysicalBody, obj_b: pycram.datastructures.world_entity.PhysicalBody, max_distance: float) -> pycram.datastructures.dataclasses.ClosestPointsList


   .. py:method:: get_body_and_link_id(body: pycram.datastructures.world_entity.PhysicalBody, index='') -> typing_extensions.Dict[str, int]
      :staticmethod:



   .. py:method:: parse_points_list_to_args(point: typing_extensions.List) -> typing_extensions.Dict

      Parses the list of points to a list of dictionaries with the keys as the names of the arguments of the
      ContactPoint class.

      :param point: The list of points.



   .. py:method:: _set_multiple_joint_positions(joint_positions: typing_extensions.Dict[Joint, float]) -> bool


   .. py:method:: _reset_joint_position(joint: Joint, joint_position: float) -> bool


   .. py:method:: _get_multiple_joint_positions(joints: typing_extensions.List[Joint]) -> typing_extensions.Dict[str, float]


   .. py:method:: reset_multiple_objects_base_poses(objects: typing_extensions.Dict[pycram.world_concepts.world_object.Object, pycram.datastructures.pose.PoseStamped]) -> bool


   .. py:method:: reset_object_base_pose(obj: pycram.world_concepts.world_object.Object, pose: pycram.datastructures.pose.PoseStamped) -> bool


   .. py:method:: _set_object_pose_by_id(obj_id: int, pose: pycram.datastructures.pose.PoseStamped) -> bool


   .. py:method:: step(func: typing_extensions.Optional[typing_extensions.Callable[[], None]] = None, step_seconds: typing_extensions.Optional[float] = None) -> None


   .. py:method:: get_multiple_object_poses(objects: typing_extensions.List[pycram.world_concepts.world_object.Object]) -> typing_extensions.Dict[str, pycram.datastructures.pose.PoseStamped]


   .. py:method:: get_multiple_object_positions(objects: typing_extensions.List[pycram.world_concepts.world_object.Object]) -> typing_extensions.Dict[str, typing_extensions.List[float]]


   .. py:method:: get_multiple_object_orientations(objects: typing_extensions.List[pycram.world_concepts.world_object.Object]) -> typing_extensions.Dict[str, typing_extensions.List[float]]


   .. py:method:: get_object_position(obj: pycram.world_concepts.world_object.Object) -> typing_extensions.List[float]


   .. py:method:: get_object_orientation(obj: pycram.world_concepts.world_object.Object) -> typing_extensions.List[float]


   .. py:method:: get_object_pose(obj: pycram.world_concepts.world_object.Object) -> pycram.datastructures.pose.PoseStamped


   .. py:method:: set_link_color(link: pycram.object_descriptors.urdf.ObjectDescription.Link, rgba_color: pycram.datastructures.dataclasses.Color)


   .. py:method:: get_link_color(link: pycram.object_descriptors.urdf.ObjectDescription.Link) -> pycram.datastructures.dataclasses.Color


   .. py:method:: get_colors_of_object_links(obj: pycram.world_concepts.world_object.Object) -> typing_extensions.Dict[str, pycram.datastructures.dataclasses.Color]


   .. py:method:: get_object_axis_aligned_bounding_box(obj: pycram.world_concepts.world_object.Object) -> pycram.datastructures.dataclasses.AxisAlignedBoundingBox


   .. py:method:: get_link_axis_aligned_bounding_box(link: pycram.object_descriptors.urdf.ObjectDescription.Link) -> pycram.datastructures.dataclasses.AxisAlignedBoundingBox


   .. py:method:: set_realtime(real_time: bool) -> None


   .. py:method:: set_gravity(gravity_vector: typing_extensions.List[float]) -> None


   .. py:method:: disconnect_from_physics_server()


   .. py:method:: join_threads()

      Joins the GUI thread if it exists.



   .. py:method:: join_gui_thread_if_exists()


   .. py:method:: save_physics_simulator_state(state_id: typing_extensions.Optional[int] = None, use_same_id: bool = False) -> int


   .. py:method:: restore_physics_simulator_state(state_id)


   .. py:method:: remove_physics_simulator_state(state_id: int)


   .. py:method:: _add_vis_axis(pose: pycram.datastructures.pose.PoseStamped, length: typing_extensions.Optional[float] = 0.2) -> int

      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.

      :param pose: The pose at which the axis should be spawned
      :param length: Optional parameter to configure the length of the axes
      :return: The id of the spawned object



   .. py:method:: _remove_vis_axis() -> None

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



   .. py:method:: _ray_test(from_position: typing_extensions.List[float], to_position: typing_extensions.List[float]) -> pycram.datastructures.dataclasses.RayResult


   .. py:method:: _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[pycram.datastructures.dataclasses.RayResult]


   .. py:method:: _create_visual_shape(visual_shape: pycram.datastructures.dataclasses.VisualShape) -> int


   .. py:method:: _create_multi_body(multi_body: pycram.datastructures.dataclasses.MultiBody) -> int


   .. py:method:: get_images_for_target(target_pose: pycram.datastructures.pose.PoseStamped, cam_pose: pycram.datastructures.pose.PoseStamped, size: typing_extensions.Optional[int] = 256) -> typing_extensions.List[numpy.ndarray]


   .. py:method:: _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


   .. py:method:: _remove_text(text_id: typing_extensions.Optional[int] = None) -> None


   .. py:method:: enable_joint_force_torque_sensor(obj: pycram.world_concepts.world_object.Object, fts_joint_idx: int) -> None


   .. py:method:: disable_joint_force_torque_sensor(obj: pycram.world_concepts.world_object.Object, joint_id: int) -> None


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


   .. py:method:: get_applied_joint_motor_torque(obj: pycram.world_concepts.world_object.Object, joint_id: int) -> float


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

   Bases: :py:obj:`threading.Thread`


   For internal use only. Creates a new thread for the physics simulation that is active until closed by
   :func:`~World.exit`
   Also contains the code for controlling the camera.


   .. py:attribute:: world


   .. py:attribute:: mode
      :type:  pycram.datastructures.enums.WorldMode


   .. py:attribute:: camera_button_id
      :value: -1



   .. py:method:: 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.



