diff --git a/examples/pybullet/examples/inverse_kinematics_husky_kuka.py b/examples/pybullet/examples/inverse_kinematics_husky_kuka.py index 7b3bb793d..256d57ae6 100644 --- a/examples/pybullet/examples/inverse_kinematics_husky_kuka.py +++ b/examples/pybullet/examples/inverse_kinematics_husky_kuka.py @@ -3,8 +3,11 @@ import time import math from datetime import datetime from datetime import datetime +import pybullet_data clid = p.connect(p.SHARED_MEMORY) + +p.setAdditionalSearchPath(pybullet_data.getDataPath()) if (clid < 0): p.connect(p.GUI) p.loadURDF("plane.urdf", [0, 0, -0.3])