fix for Python 2.x

This commit is contained in:
Erwin Coumans
2018-01-08 16:15:54 -08:00
parent f39d83580b
commit 90c5d66e1b
3 changed files with 5 additions and 4 deletions

View File

@@ -552,7 +552,7 @@ if (1):
for i in range (p.getNumJoints(obUid, physicsClientId=gui)):
p.setJointMotorControl2(obUid,i,p.VELOCITY_CONTROL,targetVelocity=0.1,force=1,physicsClientId=gui)
p.setJointMotorControl2(obUid,i,p.VELOCITY_CONTROL,targetVelocity=0,force=1,physicsClientId=gui)
print(p.getJointInfo(obUid,i,physicsClientId=gui))
@@ -562,5 +562,6 @@ p.setRealTimeSimulation(1,physicsClientId=gui)
while (p.getConnectionInfo(physicsClientId=gui)["isConnected"]):
p.stepSimulation(physicsClientId=gui)
time.sleep(0.01)

View File

@@ -5800,7 +5800,7 @@ static PyObject* pybullet_createCollisionShapeArray(PyObject* self, PyObject* ar
PyObject* ob = PyUnicode_AsASCIIString(fileNameObj);
fileName = PyBytes_AS_STRING(ob);
#else
fileName = PyString_AsString(objectsRepresentation);
fileName = PyString_AsString(fileNameObj);
#endif
}
if (meshScaleObj)