It is not uncommon to find this line in PyBullet examples:
p.setPhysicsEngineParameter(deterministicOverlappingPairs=1)
What is the purpose of the "deterministicOverlappingPairs" setting? Why should I set it?
I have looked at the documentation and found out that this setting is related to collision detection. However, what exactly is happening under the hood was not explained in the documentation.
A basic script that allows testing the setting by calling it with the "--dop" argument set to 0 or 1 is provided below. The argument is passed into the function on line 11:
import pybullet as p
import pybullet_data
import argparse
from datetime import datetime
numSteps = 500
numObjects = 50
def setupWorld(dop):
p.resetSimulation()
# The line I am interested in
p.setPhysicsEngineParameter(deterministicOverlappingPairs=dop)
p.loadURDF("plane.urdf")
kukaId = p.loadURDF("kuka_iiwa/model_free_base.urdf", [0, 0, 10])
for i in range(p.getNumJoints(kukaId)):
p.setJointMotorControl2(kukaId, i, p.POSITION_CONTROL, force=0)
for i in range(numObjects):
cube = p.loadURDF("cube_small.urdf", [0, i * 0.02, (i + 1) * 0.2])
p.stepSimulation()
p.setGravity(0, 0, -10)
if __name__ == '__main__':
parser = argparse.ArgumentParser(description='Select run mode')
parser.add_argument('--dop', metavar=1, type=int,
help='Set value for deterministicOverlappingPairs')
args = parser.parse_args()
p.connect(p.GUI, options="--width=1024 --height=768")
p.setAdditionalSearchPath(pybullet_data.getDataPath())
start_time = datetime.now()
setupWorld(args.dop)
for i in range(numSteps):
p.stepSimulation()
print(f"Runtime = {datetime.now()-start_time}")
By running this script with the command line arguments "--dop 0" and "--dop 1", I did not notice a significant change in runtime.
Since, I do not know how deterministicOverlappingPairs is supposed to affect the simulation, I am unable to provide an example script that has a measurable output related to deterministicOverlappingPairs.