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
Links and Joints
Objects spawned from mesh files do not have links or joints, but if you spawn things from a URDF like a robot they will have a lot of links and joints. Every Object has two dictionaries as attributes, namely links
and joints
which contain every link or joint as key and a unique id, used by PyBullet, as value.
We will see this at the example of the PR2:
[11]:
pr2 = Object("pr2", ObjectType.ROBOT, "pr2.urdf")
print(pr2.links)
{'base_link': <pycram.world.Link object at 0x7f694d986d30>, 'base_footprint': <pycram.world.RootLink object at 0x7f694d986d00>, 'base_bellow_link': <pycram.world.Link object at 0x7f694d986cd0>, 'base_laser_link': <pycram.world.Link object at 0x7f694d986ca0>, 'fl_caster_rotation_link': <pycram.world.Link object at 0x7f694d986c70>, 'fl_caster_l_wheel_link': <pycram.world.Link object at 0x7f694d986c40>, 'fl_caster_r_wheel_link': <pycram.world.Link object at 0x7f694d986c10>, 'fr_caster_rotation_link': <pycram.world.Link object at 0x7f694d986be0>, 'fr_caster_l_wheel_link': <pycram.world.Link object at 0x7f694d986bb0>, 'fr_caster_r_wheel_link': <pycram.world.Link object at 0x7f694d986b80>, 'bl_caster_rotation_link': <pycram.world.Link object at 0x7f694d986b50>, 'bl_caster_l_wheel_link': <pycram.world.Link object at 0x7f694d986b20>, 'bl_caster_r_wheel_link': <pycram.world.Link object at 0x7f694d986af0>, 'br_caster_rotation_link': <pycram.world.Link object at 0x7f694d986ac0>, 'br_caster_l_wheel_link': <pycram.world.Link object at 0x7f694d986a90>, 'br_caster_r_wheel_link': <pycram.world.Link object at 0x7f694d986a60>, 'torso_lift_link': <pycram.world.Link object at 0x7f694d986a30>, 'l_torso_lift_side_plate_link': <pycram.world.Link object at 0x7f694d986a00>, 'r_torso_lift_side_plate_link': <pycram.world.Link object at 0x7f694d9869d0>, 'torso_lift_motor_screw_link': <pycram.world.Link object at 0x7f694d9869a0>, 'imu_link': <pycram.world.Link object at 0x7f694d986970>, 'head_pan_link': <pycram.world.Link object at 0x7f694d986940>, 'head_tilt_link': <pycram.world.Link object at 0x7f694d986910>, 'head_plate_frame': <pycram.world.Link object at 0x7f694d9868e0>, 'sensor_mount_link': <pycram.world.Link object at 0x7f694d986880>, 'high_def_frame': <pycram.world.Link object at 0x7f694d9868b0>, 'high_def_optical_frame': <pycram.world.Link object at 0x7f694d986850>, 'double_stereo_link': <pycram.world.Link object at 0x7f694d986820>, 'wide_stereo_link': <pycram.world.Link object at 0x7f694d9867f0>, 'wide_stereo_optical_frame': <pycram.world.Link object at 0x7f694d9867c0>, 'wide_stereo_l_stereo_camera_frame': <pycram.world.Link object at 0x7f694d986790>, 'wide_stereo_l_stereo_camera_optical_frame': <pycram.world.Link object at 0x7f694d986760>, 'wide_stereo_r_stereo_camera_frame': <pycram.world.Link object at 0x7f694d986730>, 'wide_stereo_r_stereo_camera_optical_frame': <pycram.world.Link object at 0x7f694d986700>, 'narrow_stereo_link': <pycram.world.Link object at 0x7f694d9866d0>, 'narrow_stereo_optical_frame': <pycram.world.Link object at 0x7f694d9866a0>, 'narrow_stereo_l_stereo_camera_frame': <pycram.world.Link object at 0x7f694d986670>, 'narrow_stereo_l_stereo_camera_optical_frame': <pycram.world.Link object at 0x7f694d986640>, 'narrow_stereo_r_stereo_camera_frame': <pycram.world.Link object at 0x7f694d986610>, 'narrow_stereo_r_stereo_camera_optical_frame': <pycram.world.Link object at 0x7f694d9865e0>, 'projector_wg6802418_frame': <pycram.world.Link object at 0x7f694d9865b0>, 'projector_wg6802418_child_frame': <pycram.world.Link object at 0x7f694d986580>, 'laser_tilt_mount_link': <pycram.world.Link object at 0x7f694d986490>, 'laser_tilt_link': <pycram.world.Link object at 0x7f694d986460>, 'r_shoulder_pan_link': <pycram.world.Link object at 0x7f694d986430>, 'r_shoulder_lift_link': <pycram.world.Link object at 0x7f694d986400>, 'r_upper_arm_roll_link': <pycram.world.Link object at 0x7f694d9863d0>, 'r_upper_arm_link': <pycram.world.Link object at 0x7f694d9863a0>, 'r_forearm_roll_link': <pycram.world.Link object at 0x7f694d986370>, 'r_elbow_flex_link': <pycram.world.Link object at 0x7f694d986340>, 'r_forearm_link': <pycram.world.Link object at 0x7f694d986310>, 'r_wrist_flex_link': <pycram.world.Link object at 0x7f694d9862e0>, 'r_wrist_roll_link': <pycram.world.Link object at 0x7f694d9862b0>, 'r_gripper_palm_link': <pycram.world.Link object at 0x7f694d986280>, 'r_gripper_led_frame': <pycram.world.Link object at 0x7f694d986250>, 'r_gripper_motor_accelerometer_link': <pycram.world.Link object at 0x7f694d986220>, 'r_gripper_tool_frame': <pycram.world.Link object at 0x7f694d9861f0>, 'r_gripper_motor_slider_link': <pycram.world.Link object at 0x7f694d9861c0>, 'r_gripper_motor_screw_link': <pycram.world.Link object at 0x7f694d986190>, 'r_gripper_l_finger_link': <pycram.world.Link object at 0x7f694d986160>, 'r_gripper_r_finger_link': <pycram.world.Link object at 0x7f694d986130>, 'r_gripper_l_finger_tip_link': <pycram.world.Link object at 0x7f694d9860d0>, 'r_gripper_r_finger_tip_link': <pycram.world.Link object at 0x7f694d986100>, 'r_gripper_l_finger_tip_frame': <pycram.world.Link object at 0x7f694d9860a0>, 'l_shoulder_pan_link': <pycram.world.Link object at 0x7f694d986070>, 'l_shoulder_lift_link': <pycram.world.Link object at 0x7f694d986040>, 'l_upper_arm_roll_link': <pycram.world.Link object at 0x7f69508d1fd0>, 'l_upper_arm_link': <pycram.world.Link object at 0x7f69508d1fa0>, 'l_forearm_roll_link': <pycram.world.Link object at 0x7f69508d1f70>, 'l_elbow_flex_link': <pycram.world.Link object at 0x7f69508d1f40>, 'l_forearm_link': <pycram.world.Link object at 0x7f69508d1f10>, 'l_wrist_flex_link': <pycram.world.Link object at 0x7f69508d1ee0>, 'l_wrist_roll_link': <pycram.world.Link object at 0x7f69508d1eb0>, 'l_gripper_palm_link': <pycram.world.Link object at 0x7f69508d1e80>, 'l_gripper_led_frame': <pycram.world.Link object at 0x7f69508d1e20>, 'l_gripper_motor_accelerometer_link': <pycram.world.Link object at 0x7f69508d1e50>, 'l_gripper_tool_frame': <pycram.world.Link object at 0x7f69508d1dc0>, 'l_gripper_motor_slider_link': <pycram.world.Link object at 0x7f69508d1df0>, 'l_gripper_motor_screw_link': <pycram.world.Link object at 0x7f69508d1d90>, 'l_gripper_l_finger_link': <pycram.world.Link object at 0x7f69508d1d60>, 'l_gripper_r_finger_link': <pycram.world.Link object at 0x7f69508d1d00>, 'l_gripper_l_finger_tip_link': <pycram.world.Link object at 0x7f69508d1d30>, 'l_gripper_r_finger_tip_link': <pycram.world.Link object at 0x7f69508d1ca0>, 'l_gripper_l_finger_tip_frame': <pycram.world.Link object at 0x7f69508d1cd0>, 'l_forearm_cam_frame': <pycram.world.Link object at 0x7f69508d1c70>, 'l_forearm_cam_optical_frame': <pycram.world.Link object at 0x7f69508d1c40>, 'r_forearm_cam_frame': <pycram.world.Link object at 0x7f69508d1c10>, 'r_forearm_cam_optical_frame': <pycram.world.Link object at 0x7f69508d1be0>}
For links there are similar methods available as for the pose. However, you can only get the position and orientation of a link.
[12]:
print(f"Position: \n{pr2.get_link_position('torso_lift_link')}")
print(f"Orientation: \n{pr2.get_link_orientation('torso_lift_link')}")
print(f"Pose: \n{pr2.get_link_pose('torso_lift_link')}")
Position:
x: -0.05000000447034836
y: 0.0
z: 0.7906750440597534
Orientation:
x: 0.0
y: 0.0
z: 0.0
w: 1.0
Pose:
header:
seq: 0
stamp:
secs: 1706207426
nsecs: 257559537
frame_id: "map"
pose:
position:
x: -0.05000000447034836
y: 0.0
z: 0.7906750440597534
orientation:
x: 0.0
y: 0.0
z: 0.0
w: 1.0
Methods available for joints are:
get_joint_state
set_joint_state
get_joint_limits
We will see how these methods work at the example of the torso_lift_joint:
[13]:
print(f"Joint limits: {pr2.get_joint_limits('torso_lift_joint')}")
print(f"Current Joint state: {pr2.get_joint_position('torso_lift_joint')}")
pr2.set_joint_position("torso_lift_joint", 0.2)
print(f"New Joint state: {pr2.get_joint_position('torso_lift_joint')}")
Joint limits: (0.0, 0.33)
Current Joint state: 0.0
New Joint state: 0.2
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)