Tutorials

Path creation

Generating paths

Paths are used frequently in pybullet industrial, e.g. for milling or 3d printing purposes. There are a variety of options for creating a path that will be explained in this tutorial.

A path contains a 3-dimensional array with each dimension containing subsequent positions. These data points can be specified or can be created automatically by using the built-in functions of pybullet industrial.

A box with rounded corners can be created by the use of build_box_path().

 1import numpy as np
 2import pybullet as p
 3import pybullet_industrial as pi
 4
 5if __name__ == "__main__":
 6
 7    p.connect(p.GUI)
 8    # disable rendering during path drawing for better performance
 9    p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0)
10
11    # creates a blue box path with rounded corners
12    test_path = pi.build_box_path(
13        [0, 3, 0], [4, 2], 0.7, p.getQuaternionFromEuler([np.pi/2, 0, 0]), 100)
14    test_path.draw()
15    while (1):
16        p.stepSimulation()

For positioning the path an array for the center position is specified along with the dimensions of the box and the radius of its corners. The path is rotated by 90 degrees around the x-axis using the transformation function of pybullet. In this case, the path contains 100 points. A circle can be generated similarly. After the paths are created, they are drawn. The default color of a path is blue. The result looks like this:

box_path

You can generate a path between two points by utilizing interpolation functions. Here the color of the paths is prescribed.

 1import numpy as np
 2import pybullet as p
 3import pybullet_industrial as pi
 4
 5if __name__ == "__main__":
 6
 7    p.connect(p.GUI)
 8    # disable rendering during path drawing for better performance
 9    p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0)
10    # path in the ++ quadrant
11    org_test_path = pi.linear_interpolation(
12        [0, 0, 0], [1/np.sqrt(2), 1/np.sqrt(2), 0], 10)
13    org_test_path.draw(color=[1, 0, 0])
14
15    test_path = pi.circular_interpolation(
16        np.array([0, 1, 0]), np.array([1, 0, 0]), 1, 50)
17    test_path.draw(color=[1, 0, 0])
18
19    # paths in the +- quadrant
20    test_path = pi.linear_interpolation(
21        [1, -1, 0], [1-1/np.sqrt(2), -1+1/np.sqrt(2), 0], 10)
22    test_path.draw(color=[0, 1, 0])
23
24    test_path = pi.circular_interpolation(
25        np.array([0, -1, 0]), np.array([1, 0, 0]), 1, 50)
26    test_path.draw(color=[0, 1, 0])
27
28    # path in the -- quadrant
29    test_path = pi.circular_interpolation(
30        np.array([0, -1, 0]), np.array([-1, 0, 0.5]), 1, 50)
31    test_path.draw(color=[0, 0, 1])
32
33    # path in the -+ quadrant
34    test_path = pi.circular_interpolation(
35        np.array([0, 1, 0.5]), np.array([-1, 0, 0.5]), 1, 50, clockwise=False)
36    test_path.draw(color=[0, 1, 1])
37
38    test_path = pi.circular_interpolation(
39        np.array([0, 0, 0]), np.array([0, 1, 1]), 1, 50, axis=0)
40    test_path.draw(color=[1, 1, 0])
41
42    test_path = pi.circular_interpolation(
43        np.array([0, 0, 0]), np.array([1, 0, 1]), 1, 50, axis=1)
44    test_path.draw(color=[1, 1, 0])
45
46    test_path = pi.spline_interpolation(
47        [[0, 1, 0], [0, 0, 1], [0, 1, 1]], samples=50)
48    test_path.draw(color=[1, 0.5, 0.5])
49    while (1):
50        p.stepSimulation()
interpolation_example

Manipulating paths

Sometimes it can be useful to translate an entire path by a given vector. Similarly, you can rotate a path by a prescribed quaternion. Finally, a path can be appended or prepended to another path, as shown here:

 1import numpy as np
 2import pybullet as p
 3import pybullet_industrial as pi
 4
 5if __name__ == "__main__":
 6
 7    p.connect(p.GUI)
 8    # disable rendering during path drawing for better performance
 9    p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0)
10    test_path = pi.spline_interpolation(
11        [[0, 1, 0], [0, 0, 1], [0, 1, 1]], samples=50)
12    test_path.draw(color=[1, 0.5, 0.5])
13
14    test_path.translate([0, 0, 1])
15    test_path.draw(pose=True)
16
17    test_path.append(org_test_path)
18    test_path.prepend(org_test_path)
19
20    test_path.rotate(p.getQuaternionFromEuler([np.pi/2, 0, 0]))
21    test_path.draw(pose=True)
22
23    p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1)
24
25    while (1):
26        p.stepSimulation()

3d printing and milling

In this tutorial a robot prints and mills particles alternately. To make a robot follow a path and print particles, the simulation must be set up first.

To integrate a robot into a simulation its URDF file must be loaded first. Together with a position and an orientation, it can be loaded in the GUI. For the extruder and the milling tool respectively properties must be defined as well. For both the extruder and the remover a maximum distance, an opening angle, and the number of rays need to be specified. With these parameters, the tool can determine whether other objects are close enough to interact with. For the extruder, the material properties must be stated too. By coupling or decoupling a tool to a link from the robot, it can be attached or detached.

 1import os
 2
 3import numpy as np
 4import pybullet as p
 5import pybullet_data
 6import pybullet_industrial as pi
 7
 8
 9if __name__ == "__main__":
10    dirname = os.path.dirname(__file__)
11    urdf_file1 = os.path.join(dirname,
12                              'robot_descriptions', 'kuka_robot.urdf')
13    urdf_file2 = os.path.join(dirname,
14                              'robot_descriptions', '3d_printing_head.urdf')
15
16    physics_client = p.connect(p.GUI)
17    p.setPhysicsEngineParameter(numSolverIterations=5000)
18
19    p.setAdditionalSearchPath(pybullet_data.getDataPath())
20    fofa_path = os.path.join(dirname,
21                             'Objects', 'FoFa', 'FoFa.urdf')
22    p.loadURDF(fofa_path, [-4, 5, 0], useFixedBase=True, globalScaling=0.001)
23
24    start_orientation = p.getQuaternionFromEuler([0, 0, 0])
25    robot = pi.RobotBase(urdf_file1, [0, 0, 0], start_orientation)
26    extruder_properties = {'maximum distance': 0.5,
27                           'opening angle': 0,
28                           'material': pi.Plastic,
29                           'material properties': {'particle size': 0.03},
30                           'number of rays': 1}
31    extruder = pi.Extruder(
32        urdf_file2, [1.9, 0, 1.2], start_orientation, extruder_properties)
33    p.changeVisualShape(extruder.urdf, -1, rgbaColor=[1, 0, 0, 1])
34    extruder.couple(robot, 'link6')
35
36    remover_properties = {'maximum distance': 0.02,
37                          'opening angle': 0,
38                          'number of rays': 1}
39    remover = pi.Remover(
40        urdf_file2, [1.9, 1, 1.2], start_orientation, remover_properties)
41    p.changeVisualShape(remover.urdf, -1, rgbaColor=[0, 0, 1, 1])

The next step is defining the path for the tools, as it is done here with a box path.

1    # Defining a roundet rectangular path
2    target_position = np.array([1.9, 0.0, 0.53])
3    target_orientation = p.getQuaternionFromEuler([0, 0, 0])
4    test_path = pi.build_box_path(
5        target_position, [0.5, 0.6], 0.1, [0, 0, 0, 1], 50)

Finally, the tools are translated to follow the path. First, they are positioned at the beginning of the path. For each position in the path, the tools are translated and extrude or respectively remove particles.

material_extrusion material_removal

After they reached the end of the path, the tool will be decoupled and the new tool coupled to the robot.

 1
 2    for _ in range(20):
 3        extruder.set_tool_pose(*test_path.get_start_pose())
 4        for _ in range(50):
 5            p.stepSimulation()
 6    p.loadURDF("cube.urdf", [1.9, 0, 0], useFixedBase=True)
 7
 8    test_path.draw()
 9
10    extruding = 1
11    while True:
12        for _ in range(20):
13            extruder.set_tool_pose(*test_path.get_start_pose())
14            for _ in range(50):
15                p.stepSimulation()
16        if extruding:
17            for positions, orientations, tool_path in test_path:
18                extruder.set_tool_pose(positions, orientations)
19                particle = extruder.extrude()
20
21                for _ in range(30):
22                    p.stepSimulation()
23            extruder.decouple()
24            remover.couple(robot, 'link6')
25            extruding = 0
26            continue
27        if not extruding:
28            for positions, orientations, tool_path in test_path:
29                for _ in range(3):
30                    removed_particles = remover.remove()
31                remover.set_tool_pose(positions, orientations)
32                for _ in range(3):
33                    removed_particles = remover.remove()
34
35                for _ in range(30):
36                    p.stepSimulation()
37            remover.decouple()
38            extruder.couple(robot, 'link6')
39            extruding = 1