Bullet World

This Notebook will show you the basics of working with the PyCRAM BulletWorld.

First we need to import and create a BulletWorld.

[1]:
from pycram.bullet_world import BulletWorld
from pycram.pose import Pose
from pycram.enums import ObjectType, WorldMode

world = BulletWorld(mode=WorldMode.GUI)
Unknown attribute "type" in /robot[@name='pr2']/link[@name='base_laser_link']
Unknown attribute "type" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']
Unknown attribute "type" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']
Unknown attribute "type" in /robot[@name='pr2']/link[@name='laser_tilt_link']
Failed to import Giskard messages
Could not import RoboKudo messages, RoboKudo interface could not be initialized
pybullet build time: Nov 28 2023 23:51:11

This new window is the BulletWorld, PyCRAMs internal physics simulation. You can use the mouse to move the camera around:

  • Press the left mouse button to rotate the camera

  • Press the right mouse button to move the camera

  • Press the middle mouse button (scroll wheel) and move the mouse up or down to zoom

At the moment the BulletWorld only contains a floor, this is spawned by default when creating the BulletWorld. Furthermore, the gravity is set to 9.8 m^2, which is the same gravitation as the one on earth.

To close the BulletWorld again please use the exit method since it will also terminate threads running in the background

[7]:
world.exit()

To spawn new things in the BulletWorld we need to import the Object class and create and instance of it.

[2]:
from pycram.bullet_world import Object

milk = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([0, 0, 1]))

As you can see this spawns a milk floating in the air. What we did here was create a new Object which has the name “milk” as well as the type ObjectType.MILK , is spawned from the file “milk.stl” and is at the position [0, 0, 1].

The type of an Object can either be from the enum ObjectType or a string. However, it is recommended to use the enum since this would make for a more consistent naming of types which makes it easier to work with types. But since the types of the enum might not fit your case you can also use strings.

The first three of these parameters are required while the position is optional. As you can see it was sufficient to only specify the filename for PyCRAM to spawn the milk mesh. When only providing a filename, PyCRAM will search in its resource directory for a matching file and use it.

For a complete list of all parameters that can be used to crate an Object please check the documentation.

Since the Object is spawned, we can now interact with it. First we want to move it around and change its orientation

[3]:
milk.set_position(Pose([1, 1, 1]))
[4]:
milk.set_orientation(Pose(orientation=[1,0, 0, 1]))
[5]:
milk.set_pose(Pose([0, 0, 1], [0, 0, 0, 1]))

In the same sense as setting the position or orientation, you can also get the position and orientation.

[6]:
print(f"Position: \n{milk.get_position()}")

print(f"Orientation: \n{milk.get_orientation()}")

print(f"Pose: \n{milk.get_pose()}")
Position:
x: 0.0
y: 0.0
z: 1.0
Orientation:
x: 0.0
y: 0.0
z: 0.0
w: 1.0
Pose:
header:
  seq: 0
  stamp:
    secs: 1706207364
    nsecs: 174507617
  frame_id: "map"
pose:
  position:
    x: 0.0
    y: 0.0
    z: 1.0
  orientation:
    x: 0.0
    y: 0.0
    z: 0.0
    w: 1.0

Attachments

You can attach Objects to each other simply by calling the attach method on one of them and providing the other as parameter. Since attachments are bi-directional it doesn’t matter on which Object you call the method.

First we need another Object

[7]:
cereal = Object("cereal", ObjectType.BREAKFAST_CEREAL, "breakfast_cereal.stl", pose=Pose([1, 0, 1]))
[8]:
milk.attach(cereal)

Now since they are attached to each other, if we move one of them the other will move in conjunction.

[9]:
milk.set_position(Pose([1,1,1]))

In the same way the Object can also be detached, just call the detach method on one of the two attached Objects.

[10]:
cereal.detach(milk)
Removing constraint with id:  1

Misc Methods

There are a few methods that don’t fit any category but could be helpful anyway. The first two are get_color and set_color, as the name implies they can be used to get or set the color for specific links or the whole Object.

[14]:
print(f"Pr2 forearm color: {pr2.get_link_color('r_forearm_link')}")
Pr2 forearm color: Color(R=0.699999988079071, G=0.699999988079071, B=0.699999988079071, A=1.0)
[15]:
pr2.set_link_color("r_forearm_link", [1, 0, 0])

Lastly, there is get_AABB, AABB stands for Axis Aligned Bounding Box. This method returns two points in world coordinates which span a rectangle representing the AABB.

[16]:
pr2.get_axis_aligned_bounding_box()
[16]:
AxisAlignedBoundingBox(min_x=-0.0015000000000000005, min_y=-0.0015000000000000005, min_z=0.06949999999999999, max_x=0.0015000000000000005, max_y=0.0015000000000000005, max_z=0.0725)