Merge pull request #1782 from RanTig/userdata

Changes UserData to use global identifiers and makes linkIndex optional.
This commit is contained in:
erwincoumans
2018-07-09 11:36:51 +02:00
committed by GitHub
16 changed files with 478 additions and 556 deletions

View File

@@ -21,16 +21,16 @@ plane_id = client.loadURDF(PLANE_PATH)
print ("Plane ID: %s" % plane_id)
print ("Adding user data to plane")
MyKey1 = client.addUserData(plane_id, 0, "MyKey1", "MyValue1")
MyKey2 = client.addUserData(plane_id, 0, "MyKey2", "MyValue2")
MyKey3 = client.addUserData(plane_id, 0, "MyKey3", "MyValue3")
MyKey4 = client.addUserData(plane_id, 0, "MyKey4", "MyValue4")
MyKey1 = client.addUserData(plane_id, "MyKey1", "MyValue1")
MyKey2 = client.addUserData(plane_id, "MyKey2", "MyValue2")
MyKey3 = client.addUserData(plane_id, "MyKey3", "MyValue3")
MyKey4 = client.addUserData(plane_id, "MyKey4", "MyValue4")
print ("Retrieving cached user data")
print (client.getUserData(plane_id, 0, MyKey1))
print (client.getUserData(plane_id, 0, MyKey2))
print (client.getUserData(plane_id, 0, MyKey3))
print (client.getUserData(plane_id, 0, MyKey4))
print (client.getUserData(MyKey1))
print (client.getUserData(MyKey2))
print (client.getUserData(MyKey3))
print (client.getUserData(MyKey4))
print ("Disconnecting")
del client
@@ -39,18 +39,18 @@ print ("Reconnecting")
client = bullet_client.BulletClient(connection_mode=CONNECTION_METHOD)
print ("Retrieving synced user data")
print (client.getUserData(plane_id, 0, MyKey1))
print (client.getUserData(plane_id, 0, MyKey2))
print (client.getUserData(plane_id, 0, MyKey3))
print (client.getUserData(plane_id, 0, MyKey4))
print (client.getUserData(MyKey1))
print (client.getUserData(MyKey2))
print (client.getUserData(MyKey3))
print (client.getUserData(MyKey4))
print ("Number of user data entries: %s" % client.getNumUserData(plane_id, 0))
print ("Number of user data entries: %s" % client.getNumUserData(plane_id))
print ("Overriding user data")
client.addUserData(plane_id, 0, "MyKey1", "MyNewValue")
client.addUserData(plane_id, "MyKey1", "MyNewValue")
print ("Cached overridden data")
print (client.getUserData(plane_id, 0, MyKey1))
print (client.getUserData(MyKey1))
print ("Disconnecting")
@@ -61,50 +61,50 @@ client = bullet_client.BulletClient(connection_mode=CONNECTION_METHOD)
print ("Synced overridden data")
print (client.getUserData(plane_id, 0, MyKey1))
print (client.getUserData(MyKey1))
print ("Getting user data ID")
print ("Retrieved ID: %s, ID retrieved from addUserData: %s" % (client.getUserDataId(plane_id, 0, "MyKey2"), MyKey2))
print ("Retrieved ID: %s, ID retrieved from addUserData: %s" % (client.getUserDataId(plane_id, "MyKey2"), MyKey2))
print ("Removing user data")
client.removeUserData(plane_id, 0, MyKey2)
client.removeUserData(MyKey2)
print ("Retrieving cached removed data")
print (client.getUserData(plane_id, 0, MyKey2))
print (client.getUserData(MyKey2))
print ("Syncing")
client.syncUserData()
print ("Retrieving removed removed data")
print (client.getUserData(plane_id, 0, MyKey2))
print (client.getUserData(MyKey2))
print ("Iterating over all user data entries and printing results")
for i in range(client.getNumUserData(plane_id, 0)):
userDataId, key = client.getUserDataInfo(plane_id, 0, i)
print ("Info: (%s, %s)" % (userDataId, key))
print ("Value: %s" % client.getUserData(plane_id, 0, userDataId))
for i in range(client.getNumUserData(plane_id)):
userDataId, key, bodyId, linkIndex, visualShapeIndex = client.getUserDataInfo(plane_id, i)
print ("Info: (%s, %s, %s, %s, %s)" % (userDataId, key, bodyId, linkIndex, visualShapeIndex))
print ("Value: %s" % client.getUserData(userDataId))
print ("Removing body")
client.removeBody(plane_id)
print ("Retrieving user data")
print (client.getUserData(plane_id, 0, MyKey1))
print (client.getUserData(plane_id, 0, MyKey3))
print (client.getUserData(plane_id, 0, MyKey4))
print (client.getUserData(MyKey1))
print (client.getUserData(MyKey3))
print (client.getUserData(MyKey4))
print ("Syncing")
client.syncUserData()
print ("Retrieving user data")
print (client.getUserData(plane_id, 0, MyKey1))
print (client.getUserData(plane_id, 0, MyKey3))
print (client.getUserData(plane_id, 0, MyKey4))
print (client.getUserData(MyKey1))
print (client.getUserData(MyKey3))
print (client.getUserData(MyKey4))
plane_id2 = client.loadURDF(PLANE_PATH)
print ("Plane1: %s, plane2: %s" % (plane_id, plane_id2))
print ("Retrieving user data")
print (client.getUserData(plane_id, 0, MyKey1))
print (client.getUserData(plane_id, 0, MyKey3))
print (client.getUserData(plane_id, 0, MyKey4))
print (client.getUserData(MyKey1))
print (client.getUserData(MyKey3))
print (client.getUserData(MyKey4))

View File

@@ -713,18 +713,19 @@ static PyObject* pybullet_addUserData(PyObject* self, PyObject* args, PyObject*
b3PhysicsClientHandle sm = 0;
int physicsClientId = 0;
int bodyUniqueId = -1;
int linkIndex = -2;
int linkIndex = -1;
int visualShapeIndex = -1;
const char* key = "";
const char* value = ""; // TODO: Change this to a PyObject and detect the type dynamically.
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "key", "value", "physicsClientId", NULL};
static char* kwlist[] = {"bodyUniqueId", "key", "value", "linkIndex", "visualShapeIndex", "physicsClientId", NULL};
b3SharedMemoryCommandHandle command;
b3SharedMemoryStatusHandle statusHandle;
int statusType;
int userDataId;
int valueLen=-1;
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iiss|i", kwlist, &bodyUniqueId, &linkIndex, &key, &value, &physicsClientId))
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iss|iii", kwlist, &bodyUniqueId, &key, &value, &linkIndex, &visualShapeIndex, &physicsClientId))
{
return NULL;
}
@@ -736,7 +737,7 @@ static PyObject* pybullet_addUserData(PyObject* self, PyObject* args, PyObject*
}
valueLen = strlen(value)+1;
command = b3InitAddUserDataCommand(sm, bodyUniqueId, linkIndex, key, USER_DATA_VALUE_TYPE_STRING, valueLen, value);
command = b3InitAddUserDataCommand(sm, bodyUniqueId, linkIndex, visualShapeIndex, key, USER_DATA_VALUE_TYPE_STRING, valueLen, value);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
statusType = b3GetStatusType(statusHandle);
@@ -754,16 +755,14 @@ static PyObject* pybullet_removeUserData(PyObject* self, PyObject* args, PyObjec
{
b3PhysicsClientHandle sm = 0;
int physicsClientId = 0;
int bodyUniqueId = -1;
int linkIndex = -1;
int userDataId = -1;
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "userDataId", "physicsClientId", NULL};
static char* kwlist[] = {"userDataId", "physicsClientId", NULL};
b3SharedMemoryCommandHandle command;
b3SharedMemoryStatusHandle statusHandle;
int statusType;
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iii|i", kwlist, &bodyUniqueId, &linkIndex, &userDataId, &physicsClientId))
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist, &userDataId, &physicsClientId))
{
return NULL;
}
@@ -774,7 +773,7 @@ static PyObject* pybullet_removeUserData(PyObject* self, PyObject* args, PyObjec
return NULL;
}
command = b3InitRemoveUserDataCommand(sm, bodyUniqueId, linkIndex, userDataId);
command = b3InitRemoveUserDataCommand(sm, userDataId);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
statusType = b3GetStatusType(statusHandle);
@@ -794,15 +793,16 @@ static PyObject* pybullet_getUserDataId(PyObject* self, PyObject* args, PyObject
int physicsClientId = 0;
int bodyUniqueId = -1;
int linkIndex = -1;
int visualShapeIndex = -1;
const char* key = "";
int userDataId;
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "key", "physicsClientId", NULL};
static char* kwlist[] = {"bodyUniqueId", "key", "linkIndex", "visualShapeIndex", "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iis|i", kwlist, &bodyUniqueId, &linkIndex, &key, &physicsClientId))
if (!PyArg_ParseTupleAndKeywords(args, keywds, "is|iii", kwlist, &bodyUniqueId, &key, &linkIndex, &visualShapeIndex, &physicsClientId))
{
return NULL;
}
@@ -813,7 +813,7 @@ static PyObject* pybullet_getUserDataId(PyObject* self, PyObject* args, PyObject
return NULL;
}
userDataId = b3GetUserDataId(sm, bodyUniqueId, linkIndex, key);
userDataId = b3GetUserDataId(sm, bodyUniqueId, linkIndex, visualShapeIndex, key);
return PyInt_FromLong(userDataId);
}
@@ -821,16 +821,14 @@ static PyObject* pybullet_getUserData(PyObject* self, PyObject* args, PyObject*
{
b3PhysicsClientHandle sm = 0;
int physicsClientId = 0;
int bodyUniqueId = -1;
int linkIndex = -1;
int userDataId = -1;
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "userDataId", "physicsClientId", NULL};
static char* kwlist[] = {"userDataId", "physicsClientId", NULL};
struct b3UserDataValue value;
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iii|i", kwlist, &bodyUniqueId, &linkIndex, &userDataId, &physicsClientId))
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist, &userDataId, &physicsClientId))
{
return NULL;
}
@@ -842,7 +840,7 @@ static PyObject* pybullet_getUserData(PyObject* self, PyObject* args, PyObject*
}
if (!b3GetUserData(sm, bodyUniqueId, linkIndex, userDataId, &value)) {
if (!b3GetUserData(sm, userDataId, &value)) {
Py_INCREF(Py_None);
return Py_None;
@@ -861,15 +859,14 @@ static PyObject* pybullet_getNumUserData(PyObject* self, PyObject* args, PyObjec
b3PhysicsClientHandle sm = 0;
int physicsClientId = 0;
int bodyUniqueId = -1;
int linkIndex = -1;
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "physicsClientId", NULL};
static char* kwlist[] = {"bodyUniqueId", "physicsClientId", NULL};
int numUserData;
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|i", kwlist, &bodyUniqueId, &linkIndex, &physicsClientId))
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist, &bodyUniqueId, &physicsClientId))
{
return NULL;
}
@@ -880,7 +877,7 @@ static PyObject* pybullet_getNumUserData(PyObject* self, PyObject* args, PyObjec
return NULL;
}
numUserData = b3GetNumUserData(sm, bodyUniqueId, linkIndex);
numUserData = b3GetNumUserData(sm, bodyUniqueId);
return PyInt_FromLong(numUserData);
}
@@ -889,16 +886,17 @@ static PyObject* pybullet_getUserDataInfo(PyObject* self, PyObject* args, PyObje
b3PhysicsClientHandle sm = 0;
int physicsClientId = 0;
int bodyUniqueId = -1;
int linkIndex = -1;
int userDataIndex = -1;
int linkIndex = -1;
int visualShapeIndex = -1;
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "userDataIndex", "physicsClientId", NULL};
static char* kwlist[] = {"bodyUniqueId", "userDataIndex", "physicsClientId", NULL};
const char* key = 0;
int userDataId = -1;
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iii|i", kwlist, &bodyUniqueId, &linkIndex, &userDataIndex, &physicsClientId))
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|i", kwlist, &bodyUniqueId, &userDataIndex, &physicsClientId))
{
return NULL;
}
@@ -909,16 +907,19 @@ static PyObject* pybullet_getUserDataInfo(PyObject* self, PyObject* args, PyObje
return NULL;
}
b3GetUserDataInfo(sm, bodyUniqueId, linkIndex, userDataIndex, &key, &userDataId);
b3GetUserDataInfo(sm, bodyUniqueId, userDataIndex, &key, &userDataId, &linkIndex, &visualShapeIndex);
if (key == 0 || userDataId == -1) {
PyErr_SetString(SpamError, "Could not get user data info.");
return NULL;
}
{
PyObject *userDataInfoTuple = PyTuple_New(2);
PyObject *userDataInfoTuple = PyTuple_New(5);
PyTuple_SetItem(userDataInfoTuple, 0, PyInt_FromLong(userDataId));
PyTuple_SetItem(userDataInfoTuple, 1, PyString_FromString(key));
PyTuple_SetItem(userDataInfoTuple, 2, PyInt_FromLong(bodyUniqueId));
PyTuple_SetItem(userDataInfoTuple, 3, PyInt_FromLong(linkIndex));
PyTuple_SetItem(userDataInfoTuple, 4, PyInt_FromLong(visualShapeIndex));
return userDataInfoTuple;
}
}
@@ -9164,28 +9165,28 @@ static PyMethodDef SpamMethods[] = {
"Update user data, in case other clients made changes."},
{"addUserData", (PyCFunction)pybullet_addUserData, METH_VARARGS | METH_KEYWORDS,
"addUserData(bodyUniqueId, linkIndex, key, value, physicsClientId=0)\n"
"Adds or updates a user data entry to a link. Returns user data identifier."},
"addUserData(bodyUniqueId, key, value, linkIndex=-1, visualShapeIndex=-1, physicsClientId=0)\n"
"Adds or updates a user data entry. Returns user data identifier."},
{"getUserData", (PyCFunction)pybullet_getUserData, METH_VARARGS | METH_KEYWORDS,
"getUserData(bodyUniqueId, linkIndex, userDataId, physicsClientId=0)\n"
"getUserData(userDataId, physicsClientId=0)\n"
"Returns the user data value."},
{"removeUserData", (PyCFunction)pybullet_removeUserData, METH_VARARGS | METH_KEYWORDS,
"removeUserData(bodyUniqueId, linkIndex, userDataId, physicsClientId=0)\n"
"removeUserData(userDataId, physicsClientId=0)\n"
"Removes a user data entry."},
{"getUserDataId", (PyCFunction)pybullet_getUserDataId, METH_VARARGS | METH_KEYWORDS,
"getUserDataId(bodyUniqueId, linkIndex, key, physicsClientId=0)\n"
"Retrieves the userDataId on a link given the key."},
"getUserDataId(bodyUniqueId, key, linkIndex=-1, visualShapeIndex=-1, physicsClientId=0)\n"
"Retrieves the userDataId given the key and optionally link and visual shape index."},
{"getNumUserData", (PyCFunction)pybullet_getNumUserData, METH_VARARGS | METH_KEYWORDS,
"getNumUserData(bodyUniqueId, linkIndex, physicsClientId=0)\n"
"Retrieves the number of user data entries in a link."},
"getNumUserData(bodyUniqueId physicsClientId=0)\n"
"Retrieves the number of user data entries in a body."},
{"getUserDataInfo", (PyCFunction)pybullet_getUserDataInfo, METH_VARARGS | METH_KEYWORDS,
"getUserDataInfo(bodyUniqueId, linkIndex, userDataIndex, physicsClientId=0)\n"
"Retrieves the key and the identifier of a user data as (id, key)."},
"getUserDataInfo(bodyUniqueId, userDataIndex, physicsClientId=0)\n"
"Retrieves the key and the identifier of a user data as (userDataId, key, bodyUniqueId, linkIndex, visualShapeIndex)."},
{"removeBody", (PyCFunction)pybullet_removeBody, METH_VARARGS | METH_KEYWORDS,
"Remove a body by its body unique id."},

View File

@@ -26,169 +26,170 @@ class TestUserDataMethods(unittest.TestCase):
def testAddUserData(self):
plane_id = self.client.loadURDF(PLANE_PATH)
uid1 = self.client.addUserData(plane_id, 0, "MyKey1", "MyValue1")
uid2 = self.client.addUserData(plane_id, 0, "MyKey2", "MyValue2")
uid3 = self.client.addUserData(plane_id, 0, "MyKey3", "MyValue3")
uid4 = self.client.addUserData(plane_id, 0, "MyKey4", "MyValue4")
uid1 = self.client.addUserData(plane_id, "MyKey1", "MyValue1")
uid2 = self.client.addUserData(plane_id, "MyKey2", "MyValue2")
uid3 = self.client.addUserData(plane_id, "MyKey3", "MyValue3")
uid4 = self.client.addUserData(plane_id, "MyKey4", "MyValue4")
# Retrieve user data and make sure it's correct.
self.assertEqual(b"MyValue1", self.client.getUserData(plane_id, 0, uid1))
self.assertEqual(b"MyValue2", self.client.getUserData(plane_id, 0, uid2))
self.assertEqual(b"MyValue3", self.client.getUserData(plane_id, 0, uid3))
self.assertEqual(b"MyValue4", self.client.getUserData(plane_id, 0, uid4))
self.assertEqual(b"MyValue1", self.client.getUserData(uid1))
self.assertEqual(b"MyValue2", self.client.getUserData(uid2))
self.assertEqual(b"MyValue3", self.client.getUserData(uid3))
self.assertEqual(b"MyValue4", self.client.getUserData(uid4))
# Disconnect/reconnect and make sure that the user data is synced back.
del self.client
self.client = bullet_client.BulletClient(pybullet.SHARED_MEMORY)
self.assertEqual(b"MyValue1", self.client.getUserData(plane_id, 0, uid1))
self.assertEqual(b"MyValue2", self.client.getUserData(plane_id, 0, uid2))
self.assertEqual(b"MyValue3", self.client.getUserData(plane_id, 0, uid3))
self.assertEqual(b"MyValue4", self.client.getUserData(plane_id, 0, uid4))
self.assertEqual(b"MyValue1", self.client.getUserData(uid1))
self.assertEqual(b"MyValue2", self.client.getUserData(uid2))
self.assertEqual(b"MyValue3", self.client.getUserData(uid3))
self.assertEqual(b"MyValue4", self.client.getUserData(uid4))
self.client.resetSimulation()
self.assertEqual(None, self.client.getUserData(plane_id, 0, uid1))
self.assertEqual(None, self.client.getUserData(plane_id, 0, uid2))
self.assertEqual(None, self.client.getUserData(plane_id, 0, uid3))
self.assertEqual(None, self.client.getUserData(plane_id, 0, uid4))
self.assertEqual(None, self.client.getUserData(uid1))
self.assertEqual(None, self.client.getUserData(uid2))
self.assertEqual(None, self.client.getUserData(uid3))
self.assertEqual(None, self.client.getUserData(uid4))
def testGetNumUserData(self):
plane_id = self.client.loadURDF(PLANE_PATH)
uid1 = self.client.addUserData(plane_id, 0, "MyKey1", "MyValue1")
uid2 = self.client.addUserData(plane_id, 0, "MyKey2", "MyValue2")
uid3 = self.client.addUserData(plane_id, 0, "MyKey3", "MyValue3")
uid4 = self.client.addUserData(plane_id, 0, "MyKey4", "MyValue4")
uid1 = self.client.addUserData(plane_id, "MyKey1", "MyValue1")
uid2 = self.client.addUserData(plane_id, "MyKey2", "MyValue2")
uid3 = self.client.addUserData(plane_id, "MyKey3", "MyValue3")
uid4 = self.client.addUserData(plane_id, "MyKey4", "MyValue4")
self.assertEqual(4, self.client.getNumUserData(plane_id, 0))
self.assertEqual(4, self.client.getNumUserData(plane_id))
del self.client
self.client = bullet_client.BulletClient(pybullet.SHARED_MEMORY)
self.assertEqual(4, self.client.getNumUserData(plane_id, 0))
self.assertEqual(4, self.client.getNumUserData(plane_id))
def testReplaceUserData(self):
plane_id = self.client.loadURDF(PLANE_PATH)
uid = self.client.addUserData(plane_id, 0, "MyKey", "MyValue")
uid = self.client.addUserData(plane_id, "MyKey", "MyValue")
self.assertEqual(b"MyValue", self.client.getUserData(plane_id, 0, uid))
self.assertEqual(b"MyValue", self.client.getUserData(uid))
new_uid = self.client.addUserData(plane_id, 0, "MyKey", "MyNewValue")
new_uid = self.client.addUserData(plane_id, "MyKey", "MyNewValue")
self.assertEqual(uid, new_uid)
self.assertEqual(b"MyNewValue", self.client.getUserData(plane_id, 0, uid))
self.assertEqual(b"MyNewValue", self.client.getUserData(uid))
del self.client
self.client = bullet_client.BulletClient(pybullet.SHARED_MEMORY)
self.assertEqual(b"MyNewValue", self.client.getUserData(plane_id, 0, uid))
self.assertEqual(b"MyNewValue", self.client.getUserData(uid))
def testGetUserDataId(self):
plane_id = self.client.loadURDF(PLANE_PATH)
uid1 = self.client.addUserData(plane_id, 0, "MyKey1", "MyValue1")
uid2 = self.client.addUserData(plane_id, 0, "MyKey2", "MyValue2")
uid3 = self.client.addUserData(plane_id, 0, "MyKey3", "MyValue3")
uid4 = self.client.addUserData(plane_id, 0, "MyKey4", "MyValue4")
uid1 = self.client.addUserData(plane_id, "MyKey1", "MyValue1")
uid2 = self.client.addUserData(plane_id, "MyKey2", "MyValue2")
uid3 = self.client.addUserData(plane_id, "MyKey3", "MyValue3")
uid4 = self.client.addUserData(plane_id, "MyKey4", "MyValue4")
self.assertEqual(uid1, self.client.getUserDataId(plane_id, 0, "MyKey1"))
self.assertEqual(uid2, self.client.getUserDataId(plane_id, 0, "MyKey2"))
self.assertEqual(uid3, self.client.getUserDataId(plane_id, 0, "MyKey3"))
self.assertEqual(uid4, self.client.getUserDataId(plane_id, 0, "MyKey4"))
self.assertEqual(uid1, self.client.getUserDataId(plane_id, "MyKey1"))
self.assertEqual(uid2, self.client.getUserDataId(plane_id, "MyKey2"))
self.assertEqual(uid3, self.client.getUserDataId(plane_id, "MyKey3"))
self.assertEqual(uid4, self.client.getUserDataId(plane_id, "MyKey4"))
del self.client
self.client = bullet_client.BulletClient(pybullet.SHARED_MEMORY)
self.assertEqual(uid1, self.client.getUserDataId(plane_id, 0, "MyKey1"))
self.assertEqual(uid2, self.client.getUserDataId(plane_id, 0, "MyKey2"))
self.assertEqual(uid3, self.client.getUserDataId(plane_id, 0, "MyKey3"))
self.assertEqual(uid4, self.client.getUserDataId(plane_id, 0, "MyKey4"))
self.assertEqual(uid1, self.client.getUserDataId(plane_id, "MyKey1"))
self.assertEqual(uid2, self.client.getUserDataId(plane_id, "MyKey2"))
self.assertEqual(uid3, self.client.getUserDataId(plane_id, "MyKey3"))
self.assertEqual(uid4, self.client.getUserDataId(plane_id, "MyKey4"))
def testRemoveUserData(self):
plane_id = self.client.loadURDF(PLANE_PATH)
uid1 = self.client.addUserData(plane_id, 0, "MyKey1", "MyValue1")
uid2 = self.client.addUserData(plane_id, 0, "MyKey2", "MyValue2")
uid3 = self.client.addUserData(plane_id, 0, "MyKey3", "MyValue3")
uid4 = self.client.addUserData(plane_id, 0, "MyKey4", "MyValue4")
uid1 = self.client.addUserData(plane_id, "MyKey1", "MyValue1")
uid2 = self.client.addUserData(plane_id, "MyKey2", "MyValue2")
uid3 = self.client.addUserData(plane_id, "MyKey3", "MyValue3")
uid4 = self.client.addUserData(plane_id, "MyKey4", "MyValue4")
self.client.removeUserData(plane_id, 0, uid2)
self.client.removeUserData(uid2)
self.assertEqual(3, self.client.getNumUserData(plane_id, 0))
self.assertEqual(-1, self.client.getUserDataId(plane_id, 0, "MyKey2"))
self.assertEqual(None, self.client.getUserData(plane_id, 0, uid2))
self.assertEqual(b"MyValue1", self.client.getUserData(plane_id, 0, uid1))
self.assertEqual(b"MyValue3", self.client.getUserData(plane_id, 0, uid3))
self.assertEqual(b"MyValue4", self.client.getUserData(plane_id, 0, uid4))
self.assertEqual(3, self.client.getNumUserData(plane_id))
self.assertEqual(-1, self.client.getUserDataId(plane_id, "MyKey2"))
self.assertEqual(None, self.client.getUserData(uid2))
self.assertEqual(b"MyValue1", self.client.getUserData(uid1))
self.assertEqual(b"MyValue3", self.client.getUserData(uid3))
self.assertEqual(b"MyValue4", self.client.getUserData(uid4))
del self.client
self.client = bullet_client.BulletClient(pybullet.SHARED_MEMORY)
self.assertEqual(3, self.client.getNumUserData(plane_id, 0))
self.assertEqual(-1, self.client.getUserDataId(plane_id, 0, "MyKey2"))
self.assertEqual(None, self.client.getUserData(plane_id, 0, uid2))
self.assertEqual(b"MyValue1", self.client.getUserData(plane_id, 0, uid1))
self.assertEqual(b"MyValue3", self.client.getUserData(plane_id, 0, uid3))
self.assertEqual(b"MyValue4", self.client.getUserData(plane_id, 0, uid4))
self.assertEqual(3, self.client.getNumUserData(plane_id))
self.assertEqual(-1, self.client.getUserDataId(plane_id, "MyKey2"))
self.assertEqual(None, self.client.getUserData(uid2))
self.assertEqual(b"MyValue1", self.client.getUserData(uid1))
self.assertEqual(b"MyValue3", self.client.getUserData(uid3))
self.assertEqual(b"MyValue4", self.client.getUserData(uid4))
def testIterateAllUserData(self):
plane_id = self.client.loadURDF(PLANE_PATH)
uid1 = self.client.addUserData(plane_id, 0, "MyKey1", "MyValue1")
uid2 = self.client.addUserData(plane_id, 0, "MyKey2", "MyValue2")
uid3 = self.client.addUserData(plane_id, 0, "MyKey3", "MyValue3")
uid4 = self.client.addUserData(plane_id, 0, "MyKey4", "MyValue4")
uid1 = self.client.addUserData(plane_id, "MyKey1", "MyValue1")
uid2 = self.client.addUserData(plane_id, "MyKey2", "MyValue2")
uid3 = self.client.addUserData(plane_id, "MyKey3", "MyValue3")
uid4 = self.client.addUserData(plane_id, "MyKey4", "MyValue4")
entries = set()
for i in range(self.client.getNumUserData(plane_id, 0)):
userDataId, key = self.client.getUserDataInfo(plane_id, 0, i)
value = self.client.getUserData(plane_id, 0, userDataId);
entries.add((userDataId, key, value))
for i in range(self.client.getNumUserData(plane_id)):
userDataId, key, bodyId, linkIndex, visualShapeIndex = self.client.getUserDataInfo(plane_id, i)
value = self.client.getUserData(userDataId);
entries.add((userDataId, key, value, bodyId, linkIndex, visualShapeIndex))
self.assertTrue((uid1, b"MyKey1", b"MyValue1") in entries)
self.assertTrue((uid2, b"MyKey2", b"MyValue2") in entries)
self.assertTrue((uid3, b"MyKey3", b"MyValue3") in entries)
self.assertTrue((uid4, b"MyKey4", b"MyValue4") in entries)
self.assertTrue((uid1, b"MyKey1", b"MyValue1", plane_id, -1, -1) in entries)
self.assertTrue((uid2, b"MyKey2", b"MyValue2", plane_id, -1, -1) in entries)
self.assertTrue((uid3, b"MyKey3", b"MyValue3", plane_id, -1, -1) in entries)
self.assertTrue((uid4, b"MyKey4", b"MyValue4", plane_id, -1, -1) in entries)
self.assertEqual(4, len(entries))
def testRemoveBody(self):
plane_id = self.client.loadURDF(PLANE_PATH)
uid1 = self.client.addUserData(plane_id, 0, "MyKey1", "MyValue1")
uid2 = self.client.addUserData(plane_id, 0, "MyKey2", "MyValue2")
uid3 = self.client.addUserData(plane_id, 0, "MyKey3", "MyValue3")
uid4 = self.client.addUserData(plane_id, 0, "MyKey4", "MyValue4")
uid1 = self.client.addUserData(plane_id, "MyKey1", "MyValue1")
uid2 = self.client.addUserData(plane_id, "MyKey2", "MyValue2")
uid3 = self.client.addUserData(plane_id, "MyKey3", "MyValue3")
uid4 = self.client.addUserData(plane_id, "MyKey4", "MyValue4")
self.client.removeBody(plane_id)
self.assertEqual(None, self.client.getUserData(plane_id, 0, uid1))
self.assertEqual(None, self.client.getUserData(plane_id, 0, uid2))
self.assertEqual(None, self.client.getUserData(plane_id, 0, uid3))
self.assertEqual(None, self.client.getUserData(plane_id, 0, uid4))
self.assertEqual(None, self.client.getUserData(uid1))
self.assertEqual(None, self.client.getUserData(uid2))
self.assertEqual(None, self.client.getUserData(uid3))
self.assertEqual(None, self.client.getUserData(uid4))
del self.client
self.client = bullet_client.BulletClient(pybullet.SHARED_MEMORY)
self.assertEqual(None, self.client.getUserData(plane_id, 0, uid1))
self.assertEqual(None, self.client.getUserData(plane_id, 0, uid2))
self.assertEqual(None, self.client.getUserData(plane_id, 0, uid3))
self.assertEqual(None, self.client.getUserData(plane_id, 0, uid4))
self.assertEqual(None, self.client.getUserData(uid1))
self.assertEqual(None, self.client.getUserData(uid2))
self.assertEqual(None, self.client.getUserData(uid3))
self.assertEqual(None, self.client.getUserData(uid4))
def testMultipleBodies(self):
plane1 = self.client.loadURDF(PLANE_PATH)
plane2 = self.client.loadURDF(PLANE_PATH)
uid1 = self.client.addUserData(plane1, 0, "MyKey1", "This is plane 1 - 1")
uid2 = self.client.addUserData(plane1, 0, "MyKey2", "This is plane 1 - 2")
uid1 = self.client.addUserData(plane1, "MyKey1", "This is plane 1 - 1")
uid2 = self.client.addUserData(plane1, "MyKey2", "This is plane 1 - 2")
uid3 = self.client.addUserData(plane2, 0, "MyKey1", "This is plane 2 - 1")
uid4 = self.client.addUserData(plane2, 0, "MyKey2", "This is plane 2 - 2")
uid5 = self.client.addUserData(plane2, 0, "MyKey3", "This is plane 2 - 3")
uid3 = self.client.addUserData(plane2, "MyKey1", "This is plane 2 - 1")
uid4 = self.client.addUserData(plane2, "MyKey2", "This is plane 2 - 2")
uid5 = self.client.addUserData(plane2, "MyKey3", "This is plane 2 - 3")
self.assertEqual(b"This is plane 1 - 1", self.client.getUserData(plane1, 0, self.client.getUserDataId(plane1, 0, "MyKey1")))
self.assertEqual(b"This is plane 1 - 2", self.client.getUserData(plane1, 0, self.client.getUserDataId(plane1, 0, "MyKey2")))
self.assertEqual(b"This is plane 1 - 1", self.client.getUserData(self.client.getUserDataId(plane1, "MyKey1")))
self.assertEqual(b"This is plane 1 - 2", self.client.getUserData(self.client.getUserDataId(plane1, "MyKey2")))
self.assertEqual(b"This is plane 2 - 1", self.client.getUserData(plane2, 0, self.client.getUserDataId(plane2, 0, "MyKey1")))
self.assertEqual(b"This is plane 2 - 2", self.client.getUserData(plane2, 0, self.client.getUserDataId(plane2, 0, "MyKey2")))
self.assertEqual(b"This is plane 2 - 3", self.client.getUserData(plane2, 0, self.client.getUserDataId(plane2, 0, "MyKey3")))
self.assertEqual(b"This is plane 2 - 1", self.client.getUserData(self.client.getUserDataId(plane2, "MyKey1")))
self.assertEqual(b"This is plane 2 - 2", self.client.getUserData(self.client.getUserDataId(plane2, "MyKey2")))
self.assertEqual(b"This is plane 2 - 3", self.client.getUserData(self.client.getUserDataId(plane2, "MyKey3")))
def testMultipleLinks(self):
@@ -198,14 +199,15 @@ class TestUserDataMethods(unittest.TestCase):
self.assertTrue(num_links > 1)
for link_index in range(num_links):
uid1 = self.client.addUserData(body_id, link_index, "MyKey1", "Value1 for link %s" % link_index)
uid2 = self.client.addUserData(body_id, link_index, "MyKey2", "Value2 for link %s" % link_index)
uid1 = self.client.addUserData(body_id, "MyKey1", "Value1 for link %s" % link_index, link_index)
uid2 = self.client.addUserData(body_id, "MyKey2", "Value2 for link %s" % link_index, link_index)
for link_index in range(num_links):
uid1 = self.client.getUserDataId(body_id, link_index, "MyKey1")
uid2 = self.client.getUserDataId(body_id, link_index, "MyKey2")
self.assertEqual(("Value1 for link %s" % link_index).encode(), self.client.getUserData(body_id, link_index, uid1))
self.assertEqual(("Value2 for link %s" % link_index).encode(), self.client.getUserData(body_id, link_index, uid2))
uid1 = self.client.getUserDataId(body_id, "MyKey1", link_index)
uid2 = self.client.getUserDataId(body_id, "MyKey2", link_index)
self.assertEqual(("Value1 for link %s" % link_index).encode(), self.client.getUserData(uid1))
self.assertEqual(("Value2 for link %s" % link_index).encode(), self.client.getUserData(uid2))
def testMultipleClients(self):
client1 = self.client
@@ -215,25 +217,48 @@ class TestUserDataMethods(unittest.TestCase):
client2.syncBodyInfo()
# Add user data on client 1, check on client 1
uid = client1.addUserData(plane_id, 0, "MyKey", "MyValue")
self.assertEqual(None, client2.getUserData(plane_id, 0, uid))
uid = client1.addUserData(plane_id, "MyKey", "MyValue")
self.assertEqual(None, client2.getUserData(uid))
client2.syncUserData()
self.assertEqual(b"MyValue", client2.getUserData(plane_id, 0, uid))
self.assertEqual(b"MyValue", client2.getUserData(uid))
# Overwrite the value on client 2, check on client 1
client2.addUserData(plane_id, 0, "MyKey", "MyNewValue")
self.assertEqual(b"MyValue", client1.getUserData(plane_id, 0, uid))
client2.addUserData(plane_id, "MyKey", "MyNewValue")
self.assertEqual(b"MyValue", client1.getUserData(uid))
client1.syncUserData()
self.assertEqual(b"MyNewValue", client1.getUserData(plane_id, 0, uid))
self.assertEqual(b"MyNewValue", client1.getUserData(uid))
# Remove user data on client 1, check on client 2
client1.removeUserData(plane_id, 0, uid)
self.assertEqual(b"MyNewValue", client2.getUserData(plane_id, 0, uid))
client1.removeUserData(uid)
self.assertEqual(b"MyNewValue", client2.getUserData(uid))
client2.syncUserData()
self.assertEqual(None, client2.getUserData(plane_id, 0, uid))
self.assertEqual(None, client2.getUserData(uid))
del client2
def testUserDataOnVisualShapes(self):
body_id = self.client.loadURDF(ROBOT_PATH)
num_links = self.client.getNumJoints(body_id)
visual_shapes = self.client.getVisualShapeData(body_id)
self.assertTrue(num_links > 0)
self.assertTrue(len(visual_shapes) > 0)
user_data_entries = set()
for link_index in range(-1, num_links):
num_shapes = sum([1 for shape in visual_shapes if shape[1] == link_index])
for shape_index in range(num_shapes):
key = "MyKey"
value = "MyValue %s, %s" % (link_index, shape_index)
uid = self.client.addUserData(body_id, key, value, link_index, shape_index)
user_data_entries.add((uid, key, value.encode(), body_id, link_index, shape_index))
self.assertEqual(len(visual_shapes), self.client.getNumUserData(body_id))
for uid, key, value, body_id, link_index, shape_index in user_data_entries:
self.assertEqual(value, self.client.getUserData(uid))
self.assertEqual(uid, self.client.getUserDataId(body_id, key, link_index, shape_index))
if __name__ == "__main__":
unittest.main()