Scara Robot Modeling and Simulation with PyBullet

Reflect Robotics
10 min readNov 24, 2022

--

Design and control of robot arm with python programming language

ABB launches new SCARA robot range for faster, high-precision assembly

PyBullet is an Application Programming Interface (API) that allows you to have quick access to robot simulation using the Bullet Physics SDK simulation engine. Just with a robot model, you’re ready to start programming your robot right away without the need for a laborious simulation setup as you would do in Robot Operating System (ROS). It is a quick tool for research and training.

In this article, you will learn how to create a SCARA (Selective Compliance Articulated Robot Arm) model and simulate it with PyBullet using the python programming language.

By virtue of the SCARA’s parallel-axis joint layout, the arm is slightly compliant in the X-Y direction but rigid in the Z direction, hence the term selective compliance. This is advantageous for many types of assembly operations, for example, inserting a round pin in a round hole without binding. WikiPedia

Scara robot kinematics

Robot models can be designed using CAD (Computer Aided Design) software like Fusion360, SolidWorks, Blender, and FreeCAD or programmed with tools like OpenSCAD. Robot simulation software like ROS2 or PyBullet needs to read robot files in certain file formats and one of these formats is called URDF (Unified Robot Description Format) which defines the physical properties of a robot. CAD software can convert robot models to URDF but because our SCARA robot is a simple model we will write the URDF code ourselves to have a better understanding of how it works.

Our scara robot will be a 2R (2 Revolute joints) robot with 2-DOF (degrees-of-freedom) and no gripper (or end-effector).

To start learning about Robot Operating System (ROS2) for robot control, check out our comprehensive course for beginners.

Creating Our Scara Robot

We will create a file and name it scara_bot.urdf. Open this file with any text editor to start writing the code. URDF is a markup language, therefore we will start the file with the XML (Extensible Markup Language) version and the robot tag. Everything about our robot must be within the opening (<robot>) and closing (</robot>) robot tag.

<?xml version="1.0"?>
<robot name="scara_robot">

</robot>

Robots have colours, so we will define some colour materials that the links or bodies of our robot will have. These colours will be used later in the code by calling the names we give them.

<?xml version="1.0"?>
<robot name="scara_robot">
<material name="blue">
<color rgba="0.0 0.0 1.0 1.0"/>
</material>
<material name="black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
</robot>

The Base

The base of a robot is like the chassis of a car, every other part or link of that robot can be traced to it. For serial robot arms like the scara robot, the base is usually fixed to a flat surface where the robot stands. Remember that each part of the scara robot is a link connected by joints just like the human hand is connected by the shoulder and elbow joints.

Let’s create a black cylindrical base for our robot and specify its location with respect to the origin:

<?xml version="1.0"?>
<robot name="scara_robot">
<material name="blue">
<color rgba="0.0 0.0 1.0 1.0"/>
</material>
<material name="black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
<link name="world"/>
<link name="base_link">
<visual>
<origin xyz="0.0 0.0 0.4" rpy="0.0 0.0 0.0"/>
<geometry>
<cylinder length="0.8" radius="0.1"/>
</geometry>
<material name="black"/>
</visual>
</link>
</robot>

We will now make the base fixed to the world so that it doesn’t fall off. This will be achieved by creating a fixed joint between the base_link and the world link:

<?xml version="1.0"?>
<robot name="scara_robot">
<material name="blue">
<color rgba="0.0 0.0 1.0 1.0"/>
</material>
<material name="black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>

<link name="world"/>
<link name="base_link">
<visual>
<origin xyz="0.0 0.0 0.4" rpy="0.0 0.0 0.0"/>
<geometry>
<cylinder length="0.8" radius="0.1"/>
</geometry>
<material name="black"/>
</visual>
</link>
<joint name="base_joint" type="fixed">
<parent link="world"/>
<child link="base_link"/>
</joint>
</robot>

To see how your model looks, drag and drop your URDF file into this website, it will show you a 3D model of the robot.

Scara robot base from web-based URDF loader

The Upper Arm

Our scara robot will have two moveable links which will be connected together by a joint. The first link, referred to as the upper arm or arm1 will be connected to the base_link but this time the joint will not be fixed but revolute. Arm1 link whose joint rotates about the z-axis will be modeled after a box or cuboid and given a white colour.

<?xml version="1.0"?>
<robot name="scara_robot">
<material name="blue">
<color rgba="0.0 0.0 1.0 1.0"/>
</material>
<material name="black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>

<link name="world"/>
<link name="base_link">
<visual>
<origin xyz="0.0 0.0 0.4" rpy="0.0 0.0 0.0"/>
<geometry>
<cylinder length="0.8" radius="0.1"/>
</geometry>
<material name="black"/>
</visual>
</link>
<joint name="base_joint" type="fixed">
<parent link="world"/>
<child link="base_link"/>
</joint>

<link name="arm1">
<visual>
<origin xyz="0.0 -0.5 0.0" rpy="0.0 0.0 0.0"/>
<geometry>
<box size="0.1 1.0 0.1"/>
</geometry>
<material name="white"/>
</visual>
</link>
<joint name="arm1_joint" type="revolute">
<origin xyz="0.0 0.0 0.8" rpy="0.0 0.0 0.0"/>
<parent link="base_link"/>
<child link="arm1"/>
<axis xyz="0.0 0.0 1.0"/>
<limit lower="-1.0" upper="1.0" effort="1000.0" velocity="1000.0"/>
</joint>
</robot>

Let's visualize the moveable arm we just created using the web-based URDF viewer:

Scara robot arm1. Use a mouse to move the arm

The Lower Arm

The lower arm, arm2 link, will be connected to the arm1 link through a revolute joint as seen below

<?xml version="1.0"?>
<robot name="scara_robot">
<material name="blue">
<color rgba="0.0 0.0 1.0 1.0"/>
</material>
<material name="black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>

<link name="world"/>
<link name="base_link">
<visual>
<origin xyz="0.0 0.0 0.4" rpy="0.0 0.0 0.0"/>
<geometry>
<cylinder length="0.8" radius="0.1"/>
</geometry>
<material name="black"/>
</visual>
</link>
<joint name="base_joint" type="fixed">
<parent link="world"/>
<child link="base_link"/>
</joint>

<link name="arm1">
<visual>
<origin xyz="0.0 -0.5 0.0" rpy="0.0 0.0 0.0"/>
<geometry>
<box size="0.1 1.0 0.1"/>
</geometry>
<material name="white"/>
</visual>
</link>
<joint name="arm1_joint" type="revolute">
<origin xyz="0.0 0.0 0.8" rpy="0.0 0.0 0.0"/>
<parent link="base_link"/>
<child link="arm1"/>
<axis xyz="0.0 0.0 1.0"/>
<limit lower="-1.0" upper="1.0" effort="1000.0" velocity="1000.0"/>
</joint>

<link name="arm2">
<visual>
<origin xyz="0.0 -0.25 0.0" rpy="0.0 0.0 0.0"/>
<geometry>
<box size="0.1 0.5 0.1"/>
</geometry>
<material name="blue"/>
</visual>
</link>
<joint name="arm2_joint" type="revolute">
<origin xyz="0.0 -1.0 0.0" rpy="0.0 0.0 0.0"/>
<parent link="arm1"/>
<child link="arm2"/>
<axis xyz="0.0 0.0 1.0"/>
<limit lower="-1.0" upper="1.0" effort="1000.0" velocity="1000.0"/>
</joint>

</robot>

Try to visualize the full robot setup with the online URDF viewer and interact with the model by moving the links via the joints. Let’s move to the other part of this article where we write a python program using the PyBullet API to simulate our robot model.

PyBullet: Robot Simulation

The entry point to simulating a robot is having the robot model available in a format understandable by the robot simulator which we have done above. PyBullet is an API that allows you to control robot models using Python modules and the python programming language. We shall control our scara robot using the interfaces provided by PyBullet.

To install PyBullet on Linux (Ubuntu) or Mac, open the terminal (Crtl+Alt+T), copy and paste the line below:

sudo pip3 install pybullet

For Windows, follow the steps here.

The Code

Create your python file in the same directory/folder the URDF is located. Let's call it my_robot.py and open it with any preferred text editor, VS Code in our case.

Import the PyBullet module that gives you access to the API. PyBullet_data allows you to use data files that ship with PyBullet and time is a module that helps to introduce a delay in our simulation.

import pybullet as p
import pybullet_data
import time

The first thing to do after importing the modules is to connect to the physics simulation using a built-in physics server called GUI. To see what PyBullet looks like, we will run the simulation without our robot model. Not so fast! We need the stepSimulation() method to run the simulation at a default timestep of 1/240 seconds. Our code should now look like this:

import pybullet as p
import pybullet_data
import time

p.connect(p.GUI)

while True:
p.stepSimulation()
time.sleep(1./240)

If you are on VS Code you can run the code with Ctrl + F5 or open the Terminal (Ctrl + Alt + T), go to the code directory, and run the file with Python3:

$ cd scara_robot/
~/scara_robot$ python3 my_robot.py
running scara robot code

PyBullet view after running the code is shown below:

Empty PyBullet Simulation

Our simulation environment is an empty world or space that has no ground, hence our robot will fall off if we place it in this world. Let’s give this environment a floor. This floor is a blue and white tile called plane located inside PyBullet which can be accessed via the pybullet_data as shown below.

import pybullet as p
import pybullet_data
import time

p.connect(p.GUI)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
plane = p.loadURDF("plane.urdf")


while True:
p.stepSimulation()
time.sleep(1./240)

Close the simulation and run it again to see the changes

PyBullet world with the floor.

Now that we have a resting place for our robot, let's bring it into the simulation world. Use the loadURDF() method to load the scara robot and set the gravity. Objects will float or move haphazardly if gravity is not properly set.

import pybullet as p
import pybullet_data
import time

p.connect(p.GUI)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
plane = p.loadURDF("plane.urdf")
robot = p.loadURDF("scara_bot.urdf")
p.setGravity(0,0,-10)

while True:
p.stepSimulation()
time.sleep(1./240)
Scara robot in PyBullet

To control the robot, we need to be sure PyBullet understands the joints that will control the links. The getNumJoints() and getJointInfo() methods can get the number of joints in a robot and the information about each joint respectively. We will use this method to understand the joint we want to control. getNumJoints() takes a required parameter which is the robot ID we are querying to get its joint while getJointInfo() takes the robot ID and the joint number we want to query for information. We will use a for loop to query our robot ID which was named robot when we loaded the URDF.

import pybullet as p
import pybullet_data
import time

p.connect(p.GUI)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
plane = p.loadURDF("plane.urdf")
robot = p.loadURDF("scara_bot.urdf")
p.setGravity(0,0,-10)

for i in range(p.getNumJoints(robot)):
print(p.getJointInfo(robot, i))

while True:
p.stepSimulation()
time.sleep(1./240)

Run the simulation

Information about the joint.

The lower part of the picture above reveals the base_joint, arm1_joint, and arm2_joint in the parentheses. The first number in the parentheses is the index of each joint which can be used to communicate with them. Check the PyBullet manual to know more about the other details in the parentheses.

Now that we know the joints we want to control (1 and 2), let’s move on to the methods that control the joints. setJointMotorControlArray() controls the joint and takes in several parameters of which we will be using only four. The parameters are:

  • robot unique ID
  • jointIndex: this can be passed as an array.
  • controlMode: there are different modes of control in PyBullet; POSITION_CONTROL, VELOCITY_CONTROL, TORQUE_CONTROL, and PD_CONTROL. We are interested in the POSITION_CONTROL
  • targetPosition: this is where we want each joint of our robot to be.

We will move the arm1 link to position -0.456 and the arm2 link to position 0.24. The positions are in radians. The lower and upper limit defined in our URDF has constrained our robot joint to a minimum of -1 radian and a maximum of 1 radian. The joints cannot move outside of this range.

import pybullet as p
import pybullet_data
import time

p.connect(p.GUI)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
plane = p.loadURDF("plane.urdf")
robot = p.loadURDF("scara_bot.urdf")

p.setGravity(0,0,-10)
for i in range(p.getNumJoints(robot)):
print(p.getJointInfo(robot, i))

while True:
target_arm_1 = -0.456
target_arm_2 = 0.24

p.setJointMotorControlArray(robot, [1,2], p.POSITION_CONTROL, targetPositions=[target_arm_1, target_arm_2])

p.stepSimulation()
time.sleep(1./240)
The scara robot moved to the target position

The robot has moved from the default straight location to our target position. You can change the target position to see how your robot arm behaves. Congratulations on learning how to use PyBullet for robot simulation! 👏

Conclusion

You have seen how to create a simple two-degree-of-freedom (2-DOF) scara robot model in URDF format with details about the joints and axis of rotation. You also see how to use the PyBullet API to load a robot, query and get information about it, and control its joints.

The next step from here is to add another link to the robot, a prismatic joint that will make it move in a 3D space, and an end-effector otherwise called a gripper for pick-and-place of objects. If you want to learn how to simulate a robot with the Robot Operating System (ROS2) check Reflect Robotics to learn robot control with Python and C++.

If you like this article kindly click the like button and don't forget to drop a comment if you have questions, observations, corrections, or just want to appreciate the work.

--

--