PyBullet.addUserData / getUserData / removeUserData / getUserDataId / getNumUserData / getUserDataInfo

See examples/pybullet/examples/userData.py how to use it. TODO: add to PyBullet Quickstart Guide.
Thanks to Tigran Gasparian for the contribution!
This commit is contained in:
erwincoumans
2018-06-02 13:40:08 -07:00
parent cb6b7a7c38
commit b6120e760a
16 changed files with 1257 additions and 29 deletions

View File

@@ -0,0 +1,110 @@
import pybullet as pb
import time
from pybullet_utils import bullet_client
server = bullet_client.BulletClient(connection_mode=pb.GUI_SERVER)
print ("Connecting to bullet server")
CONNECTION_METHOD = pb.SHARED_MEMORY
client = bullet_client.BulletClient(connection_mode=CONNECTION_METHOD)
PLANE_PATH = "plane.urdf"
client.loadURDF(PLANE_PATH)
client.setGravity(0, 0, -10)
print ("Adding plane object")
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")
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 ("Disconnecting")
del client
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 ("Number of user data entries: %s" % client.getNumUserData(plane_id, 0))
print ("Overriding user data")
client.addUserData(plane_id, 0, "MyKey1", "MyNewValue")
print ("Cached overridden data")
print (client.getUserData(plane_id, 0, MyKey1))
print ("Disconnecting")
del client
print ("Reconnecting")
client = bullet_client.BulletClient(connection_mode=CONNECTION_METHOD)
print ("Synced overridden data")
print (client.getUserData(plane_id, 0, MyKey1))
print ("Getting user data ID")
print ("Retrieved ID: %s, ID retrieved from addUserData: %s" % (client.getUserDataId(plane_id, 0, "MyKey2"), MyKey2))
print ("Removing user data")
client.removeUserData(plane_id, 0, MyKey2)
print ("Retrieving cached removed data")
print (client.getUserData(plane_id, 0, MyKey2))
print ("Syncing")
client.syncUserData()
print ("Retrieving removed removed data")
print (client.getUserData(plane_id, 0, 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))
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 ("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))
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))

View File

@@ -487,6 +487,21 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
sNumPhysicsClients++;
return PyInt_FromLong(-1);
}
command = b3InitSyncUserDataCommand(sm);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
statusType = b3GetStatusType(statusHandle);
if (statusType != CMD_SYNC_USER_DATA_COMPLETED)
{
printf("Connection terminated, couldn't get user data\n");
b3DisconnectSharedMemory(sm);
sm = 0;
sPhysicsClients1[freeIndex] = 0;
sPhysicsClientsGUI[freeIndex] = 0;
sNumPhysicsClients++;
return PyInt_FromLong(-1);
}
}
} else
{
@@ -635,6 +650,249 @@ static PyObject* pybullet_syncBodyInfo(PyObject* self, PyObject* args, PyObject*
return Py_None;
}
static PyObject* pybullet_syncUserData(PyObject* self, PyObject* args, PyObject* keywds)
{
b3PhysicsClientHandle sm = 0;
int physicsClientId = 0;
static char* kwlist[] = {"physicsClientId", NULL};
b3SharedMemoryCommandHandle command;
b3SharedMemoryStatusHandle statusHandle;
int statusType;
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist, &physicsClientId))
{
return NULL;
}
sm = getPhysicsClient(physicsClientId);
if (sm == 0)
{
PyErr_SetString(SpamError, "Not connected to physics server.");
return NULL;
}
command = b3InitSyncUserDataCommand(sm);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
statusType = b3GetStatusType(statusHandle);
if (statusType != CMD_SYNC_USER_DATA_COMPLETED)
{
PyErr_SetString(SpamError, "Error in syncUserInfo command.");
return NULL;
}
Py_RETURN_NONE;
}
static PyObject* pybullet_addUserData(PyObject* self, PyObject* args, PyObject* keywds)
{
b3PhysicsClientHandle sm = 0;
int physicsClientId = 0;
int bodyUniqueId = -1;
int linkIndex = -2;
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};
b3SharedMemoryCommandHandle command;
b3SharedMemoryStatusHandle statusHandle;
int statusType;
int userDataId;
int valueLen=-1;
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iiss|i", kwlist, &bodyUniqueId, &linkIndex, &key, &value, &physicsClientId))
{
return NULL;
}
sm = getPhysicsClient(physicsClientId);
if (sm == 0)
{
PyErr_SetString(SpamError, "Not connected to physics server.");
return NULL;
}
valueLen = strlen(value)+1;
command = b3InitAddUserDataCommand(sm, bodyUniqueId, linkIndex, key, USER_DATA_VALUE_TYPE_STRING, valueLen, value);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
statusType = b3GetStatusType(statusHandle);
if (statusType != CMD_ADD_USER_DATA_COMPLETED)
{
PyErr_SetString(SpamError, "Error in addUserData command.");
return NULL;
}
userDataId = b3GetUserDataIdFromStatus(statusHandle);
return PyInt_FromLong(userDataId);
}
static PyObject* pybullet_removeUserData(PyObject* self, PyObject* args, PyObject* keywds)
{
b3PhysicsClientHandle sm = 0;
int physicsClientId = 0;
int bodyUniqueId = -1;
int linkIndex = -1;
int userDataId = -1;
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "userDataId", "physicsClientId", NULL};
b3SharedMemoryCommandHandle command;
b3SharedMemoryStatusHandle statusHandle;
int statusType;
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iii|i", kwlist, &bodyUniqueId, &linkIndex, &userDataId, &physicsClientId))
{
return NULL;
}
sm = getPhysicsClient(physicsClientId);
if (sm == 0)
{
PyErr_SetString(SpamError, "Not connected to physics server.");
return NULL;
}
command = b3InitRemoveUserDataCommand(sm, bodyUniqueId, linkIndex, userDataId);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
statusType = b3GetStatusType(statusHandle);
if (statusType != CMD_REMOVE_USER_DATA_COMPLETED)
{
PyErr_SetString(SpamError, "Error in removeUserData command.");
Py_RETURN_FALSE;
}
Py_RETURN_TRUE;
}
static PyObject* pybullet_getUserDataId(PyObject* self, PyObject* args, PyObject* keywds)
{
b3PhysicsClientHandle sm = 0;
int physicsClientId = 0;
int bodyUniqueId = -1;
int linkIndex = -1;
const char* key = "";
int userDataId;
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "key", "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iis|i", kwlist, &bodyUniqueId, &linkIndex, &key, &physicsClientId))
{
return NULL;
}
sm = getPhysicsClient(physicsClientId);
if (sm == 0)
{
PyErr_SetString(SpamError, "Not connected to physics server.");
return NULL;
}
userDataId = b3GetUserDataId(sm, bodyUniqueId, linkIndex, key);
return PyInt_FromLong(userDataId);
}
static PyObject* pybullet_getUserData(PyObject* self, PyObject* args, PyObject* keywds)
{
b3PhysicsClientHandle sm = 0;
int physicsClientId = 0;
int bodyUniqueId = -1;
int linkIndex = -1;
int userDataId = -1;
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "userDataId", "physicsClientId", NULL};
struct b3UserDataValue value;
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iii|i", kwlist, &bodyUniqueId, &linkIndex, &userDataId, &physicsClientId))
{
return NULL;
}
sm = getPhysicsClient(physicsClientId);
if (sm == 0)
{
PyErr_SetString(SpamError, "Not connected to physics server.");
return NULL;
}
if (!b3GetUserData(sm, bodyUniqueId, linkIndex, userDataId, &value)) {
Py_RETURN_NONE;
}
switch (value.m_type) {
case USER_DATA_VALUE_TYPE_STRING:
return PyString_FromString((const char *)value.m_data1);
default:
PyErr_SetString(SpamError, "User data value has unknown type");
return NULL;
}
}
static PyObject* pybullet_getNumUserData(PyObject* self, PyObject* args, PyObject* keywds)
{
b3PhysicsClientHandle sm = 0;
int physicsClientId = 0;
int bodyUniqueId = -1;
int linkIndex = -1;
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "physicsClientId", NULL};
int numUserData;
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|i", kwlist, &bodyUniqueId, &linkIndex, &physicsClientId))
{
return NULL;
}
sm = getPhysicsClient(physicsClientId);
if (sm == 0)
{
PyErr_SetString(SpamError, "Not connected to physics server.");
return NULL;
}
numUserData = b3GetNumUserData(sm, bodyUniqueId, linkIndex);
return PyInt_FromLong(numUserData);
}
static PyObject* pybullet_getUserDataInfo(PyObject* self, PyObject* args, PyObject* keywds)
{
b3PhysicsClientHandle sm = 0;
int physicsClientId = 0;
int bodyUniqueId = -1;
int linkIndex = -1;
int userDataIndex = -1;
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "userDataIndex", "physicsClientId", NULL};
const char* key = 0;
int userDataId = -1;
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iii|i", kwlist, &bodyUniqueId, &linkIndex, &userDataIndex, &physicsClientId))
{
return NULL;
}
sm = getPhysicsClient(physicsClientId);
if (sm == 0)
{
PyErr_SetString(SpamError, "Not connected to physics server.");
return NULL;
}
b3GetUserDataInfo(sm, bodyUniqueId, linkIndex, userDataIndex, &key, &userDataId);
if (key == 0 || userDataId == -1) {
PyErr_SetString(SpamError, "Could not get user data info.");
Py_RETURN_NONE;
}
{
PyObject *userDataInfoTuple = PyTuple_New(2);
PyTuple_SetItem(userDataInfoTuple, 0, PyInt_FromLong(userDataId));
PyTuple_SetItem(userDataInfoTuple, 1, PyString_FromString(key));
return userDataInfoTuple;
}
}
static PyObject* pybullet_saveWorld(PyObject* self, PyObject* args, PyObject* keywds)
{
@@ -8827,6 +9085,34 @@ static PyMethodDef SpamMethods[] = {
"syncBodyInfo(physicsClientId=0)\n"
"Update body and constraint/joint information, in case other clients made changes."},
{"syncUserData", (PyCFunction)pybullet_syncUserData, METH_VARARGS | METH_KEYWORDS,
"syncUserData(physicsClientId=0)\n"
"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."},
{"getUserData", (PyCFunction)pybullet_getUserData, METH_VARARGS | METH_KEYWORDS,
"getUserData(bodyUniqueId, linkIndex, userDataId, physicsClientId=0)\n"
"Returns the user data value."},
{"removeUserData", (PyCFunction)pybullet_removeUserData, METH_VARARGS | METH_KEYWORDS,
"removeUserData(bodyUniqueId, linkIndex, 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."},
{"getNumUserData", (PyCFunction)pybullet_getNumUserData, METH_VARARGS | METH_KEYWORDS,
"getNumUserData(bodyUniqueId, linkIndex, physicsClientId=0)\n"
"Retrieves the number of user data entries in a link."},
{"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)."},
{"removeBody", (PyCFunction)pybullet_removeBody, METH_VARARGS | METH_KEYWORDS,
"Remove a body by its body unique id."},