Change dynamic to dynamics in dynamics info.

This commit is contained in:
yunfeibai
2017-05-09 10:31:28 -07:00
parent 92de4ecd31
commit 98654a0cb4
9 changed files with 93 additions and 94 deletions

View File

@@ -1214,65 +1214,65 @@ int b3GetJointInfo(b3PhysicsClientHandle physClient, int bodyIndex, int jointInd
return cl->getJointInfo(bodyIndex, jointIndex, *info);
}
b3SharedMemoryCommandHandle b3GetDynamicInfoCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, int linkIndex)
b3SharedMemoryCommandHandle b3GetDynamicsInfoCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, int linkIndex)
{
PhysicsClient* cl = (PhysicsClient* ) physClient;
b3Assert(cl);
b3Assert(cl->canSubmitCommand());
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command);
command->m_type = CMD_GET_DYNAMIC_INFO;
command->m_getDynamicInfoArgs.m_bodyUniqueId = bodyUniqueId;
command->m_getDynamicInfoArgs.m_linkIndex = linkIndex;
command->m_type = CMD_GET_DYNAMICS_INFO;
command->m_getDynamicsInfoArgs.m_bodyUniqueId = bodyUniqueId;
command->m_getDynamicsInfoArgs.m_linkIndex = linkIndex;
return (b3SharedMemoryCommandHandle) command;
}
int b3GetDynamicInfo(b3SharedMemoryStatusHandle statusHandle, struct b3DynamicInfo* info)
int b3GetDynamicsInfo(b3SharedMemoryStatusHandle statusHandle, struct b3DynamicsInfo* info)
{
const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle;
const b3DynamicInfo &dynamicInfo = status->m_dynamicInfo;
btAssert(status->m_type == CMD_GET_DYNAMIC_INFO);
if (status->m_type != CMD_GET_DYNAMIC_INFO_COMPLETED)
const b3DynamicsInfo &dynamicsInfo = status->m_dynamicsInfo;
btAssert(status->m_type == CMD_GET_DYNAMICS_INFO);
if (status->m_type != CMD_GET_DYNAMICS_INFO_COMPLETED)
return false;
info->m_mass = dynamicInfo.m_mass;
info->m_lateralFrictionCoeff = dynamicInfo.m_lateralFrictionCoeff;
info->m_mass = dynamicsInfo.m_mass;
info->m_lateralFrictionCoeff = dynamicsInfo.m_lateralFrictionCoeff;
return true;
}
b3SharedMemoryCommandHandle b3InitResetDynamicInfo(b3PhysicsClientHandle physClient)
b3SharedMemoryCommandHandle b3InitResetDynamicsInfo(b3PhysicsClientHandle physClient)
{
PhysicsClient* cl = (PhysicsClient* ) physClient;
b3Assert(cl);
b3Assert(cl->canSubmitCommand());
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command);
command->m_type = CMD_RESET_DYNAMIC_INFO;
command->m_type = CMD_RESET_DYNAMICS_INFO;
command->m_updateFlags = 0;
return (b3SharedMemoryCommandHandle) command;
}
int b3ResetDynamicInfoSetMass(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double mass)
int b3ResetDynamicsInfoSetMass(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double mass)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command->m_type == CMD_RESET_DYNAMIC_INFO);
b3Assert(command->m_type == CMD_RESET_DYNAMICS_INFO);
b3Assert(mass > 0);
command->m_resetDynamicInfoArgs.m_bodyUniqueId = bodyUniqueId;
command->m_resetDynamicInfoArgs.m_linkIndex = linkIndex;
command->m_resetDynamicInfoArgs.m_mass = mass;
command->m_updateFlags |= RESET_DYNAMIC_INFO_SET_MASS;
command->m_resetDynamicsInfoArgs.m_bodyUniqueId = bodyUniqueId;
command->m_resetDynamicsInfoArgs.m_linkIndex = linkIndex;
command->m_resetDynamicsInfoArgs.m_mass = mass;
command->m_updateFlags |= RESET_DYNAMICS_INFO_SET_MASS;
return 0;
}
int b3ResetDynamicInfoSetLateralFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double lateralFriction)
int b3ResetDynamicsInfoSetLateralFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double lateralFriction)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command->m_type == CMD_RESET_DYNAMIC_INFO);
command->m_resetDynamicInfoArgs.m_bodyUniqueId = bodyUniqueId;
command->m_resetDynamicInfoArgs.m_linkIndex = linkIndex;
command->m_resetDynamicInfoArgs.m_lateralFriction = lateralFriction;
command->m_updateFlags |= RESET_DYNAMIC_INFO_SET_LATERAL_FRICTION;
b3Assert(command->m_type == CMD_RESET_DYNAMICS_INFO);
command->m_resetDynamicsInfoArgs.m_bodyUniqueId = bodyUniqueId;
command->m_resetDynamicsInfoArgs.m_linkIndex = linkIndex;
command->m_resetDynamicsInfoArgs.m_lateralFriction = lateralFriction;
command->m_updateFlags |= RESET_DYNAMICS_INFO_SET_LATERAL_FRICTION;
return 0;
}

View File

@@ -77,13 +77,13 @@ int b3GetNumJoints(b3PhysicsClientHandle physClient, int bodyIndex);
///given a body and joint index, return the joint information. See b3JointInfo in SharedMemoryPublic.h
int b3GetJointInfo(b3PhysicsClientHandle physClient, int bodyIndex, int jointIndex, struct b3JointInfo* info);
b3SharedMemoryCommandHandle b3GetDynamicInfoCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, int linkIndex);
b3SharedMemoryCommandHandle b3GetDynamicsInfoCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, int linkIndex);
///given a body unique id and link index, return the dynamic information. See b3DynamicInfo in SharedMemoryPublic.h
int b3GetDynamicInfo(b3SharedMemoryStatusHandle statusHandle, struct b3DynamicInfo* info);
int b3GetDynamicsInfo(b3SharedMemoryStatusHandle statusHandle, struct b3DynamicsInfo* info);
b3SharedMemoryCommandHandle b3InitResetDynamicInfo(b3PhysicsClientHandle physClient);
int b3ResetDynamicInfoSetMass(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double mass);
int b3ResetDynamicInfoSetLateralFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double lateralFriction);
b3SharedMemoryCommandHandle b3InitResetDynamicsInfo(b3PhysicsClientHandle physClient);
int b3ResetDynamicsInfoSetMass(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double mass);
int b3ResetDynamicsInfoSetLateralFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double lateralFriction);
b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand(b3PhysicsClientHandle physClient, int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, struct b3JointInfo* info);

View File

@@ -260,7 +260,7 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
case CMD_LOAD_SDF:
{
#ifdef BT_DEBUG
b3SharedMemoryCommandHandle commandHandle = b3LoadSdfCommandInit(m_physicsClientHandle, "kuka_iiwa/model.sdf");
b3SharedMemoryCommandHandle commandHandle = b3LoadSdfCommandInit(m_physicsClientHandle, "two_cubes.sdf");
#else
b3SharedMemoryCommandHandle commandHandle = b3LoadSdfCommandInit(m_physicsClientHandle, "kitchens/1.sdf");//two_cubes.sdf");//kitchens/1.sdf");//kuka_iiwa/model.sdf");
#endif

View File

@@ -1039,11 +1039,11 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
b3Warning("Removing body failed");
break;
}
case CMD_GET_DYNAMIC_INFO_COMPLETED:
case CMD_GET_DYNAMICS_INFO_COMPLETED:
{
break;
}
case CMD_GET_DYNAMIC_INFO_FAILED:
case CMD_GET_DYNAMICS_INFO_FAILED:
{
b3Warning("Request dynamic info failed");
break;

View File

@@ -3898,15 +3898,15 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
break;
};
case CMD_RESET_DYNAMIC_INFO:
case CMD_RESET_DYNAMICS_INFO:
{
BT_PROFILE("CMD_RESET_DYNAMIC_INFO");
BT_PROFILE("CMD_RESET_DYNAMICS_INFO");
if (clientCmd.m_updateFlags & RESET_DYNAMIC_INFO_SET_MASS)
if (clientCmd.m_updateFlags & RESET_DYNAMICS_INFO_SET_MASS)
{
int bodyUniqueId = clientCmd.m_resetDynamicInfoArgs.m_bodyUniqueId;
int linkIndex = clientCmd.m_resetDynamicInfoArgs.m_linkIndex;
double mass = clientCmd.m_resetDynamicInfoArgs.m_mass;
int bodyUniqueId = clientCmd.m_resetDynamicsInfoArgs.m_bodyUniqueId;
int linkIndex = clientCmd.m_resetDynamicsInfoArgs.m_linkIndex;
double mass = clientCmd.m_resetDynamicsInfoArgs.m_mass;
btAssert(bodyUniqueId >= 0);
btAssert(linkIndex >= -1);
@@ -3925,11 +3925,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
}
}
if (clientCmd.m_updateFlags & RESET_DYNAMIC_INFO_SET_LATERAL_FRICTION)
if (clientCmd.m_updateFlags & RESET_DYNAMICS_INFO_SET_LATERAL_FRICTION)
{
int bodyUniqueId = clientCmd.m_resetDynamicInfoArgs.m_bodyUniqueId;
int linkIndex = clientCmd.m_resetDynamicInfoArgs.m_linkIndex;
double lateralFriction = clientCmd.m_resetDynamicInfoArgs.m_lateralFriction;
int bodyUniqueId = clientCmd.m_resetDynamicsInfoArgs.m_bodyUniqueId;
int linkIndex = clientCmd.m_resetDynamicsInfoArgs.m_linkIndex;
double lateralFriction = clientCmd.m_resetDynamicsInfoArgs.m_lateralFriction;
btAssert(bodyUniqueId >= 0);
btAssert(linkIndex >= -1);
@@ -3955,26 +3955,26 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
break;
};
case CMD_GET_DYNAMIC_INFO:
case CMD_GET_DYNAMICS_INFO:
{
int bodyUniqueId = clientCmd.m_getDynamicInfoArgs.m_bodyUniqueId;
int linkIndex = clientCmd.m_getDynamicInfoArgs.m_linkIndex;
int bodyUniqueId = clientCmd.m_getDynamicsInfoArgs.m_bodyUniqueId;
int linkIndex = clientCmd.m_getDynamicsInfoArgs.m_linkIndex;
InteralBodyData* body = m_data->m_bodyHandles.getHandle(bodyUniqueId);
if (body && body->m_multiBody)
{
SharedMemoryStatus& serverCmd = serverStatusOut;
serverCmd.m_type = CMD_GET_DYNAMIC_INFO_COMPLETED;
serverCmd.m_type = CMD_GET_DYNAMICS_INFO_COMPLETED;
btMultiBody* mb = body->m_multiBody;
if (linkIndex == -1)
{
serverCmd.m_dynamicInfo.m_mass = mb->getBaseMass();
serverCmd.m_dynamicInfo.m_lateralFrictionCoeff = mb->getBaseCollider()->getFriction();
serverCmd.m_dynamicsInfo.m_mass = mb->getBaseMass();
serverCmd.m_dynamicsInfo.m_lateralFrictionCoeff = mb->getBaseCollider()->getFriction();
}
else
{
serverCmd.m_dynamicInfo.m_mass = mb->getLinkMass(linkIndex);
serverCmd.m_dynamicInfo.m_lateralFrictionCoeff = mb->getLinkCollider(linkIndex)->getFriction();
serverCmd.m_dynamicsInfo.m_mass = mb->getLinkMass(linkIndex);
serverCmd.m_dynamicsInfo.m_lateralFrictionCoeff = mb->getLinkCollider(linkIndex)->getFriction();
}
hasStatus = true;
}
@@ -3982,7 +3982,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
{
b3Warning("The dynamic info requested is not available");
SharedMemoryStatus& serverCmd = serverStatusOut;
serverCmd.m_type = CMD_GET_DYNAMIC_INFO_FAILED;
serverCmd.m_type = CMD_GET_DYNAMICS_INFO_FAILED;
hasStatus = true;
}
break;

View File

@@ -106,14 +106,14 @@ struct BulletDataStreamArgs
char m_bodyName[MAX_FILENAME_LENGTH];
};
enum EnumResetDynamicInfoFlags
enum EnumResetDynamicsInfoFlags
{
RESET_DYNAMIC_INFO_SET_MASS=1,
RESET_DYNAMIC_INFO_SET_COM=2,
RESET_DYNAMIC_INFO_SET_LATERAL_FRICTION=4,
RESET_DYNAMICS_INFO_SET_MASS=1,
RESET_DYNAMICS_INFO_SET_COM=2,
RESET_DYNAMICS_INFO_SET_LATERAL_FRICTION=4,
};
struct ResetDynamicInfoArgs
struct ResetDynamicsInfoArgs
{
int m_bodyUniqueId;
int m_linkIndex;
@@ -122,7 +122,7 @@ struct ResetDynamicInfoArgs
double m_lateralFriction;
};
struct GetDynamicInfoArgs
struct GetDynamicsInfoArgs
{
int m_bodyUniqueId;
int m_linkIndex;
@@ -744,8 +744,8 @@ struct SharedMemoryCommand
struct MjcfArgs m_mjcfArguments;
struct FileArgs m_fileArguments;
struct SdfRequestInfoArgs m_sdfRequestInfoArgs;
struct ResetDynamicInfoArgs m_resetDynamicInfoArgs;
struct GetDynamicInfoArgs m_getDynamicInfoArgs;
struct ResetDynamicsInfoArgs m_resetDynamicsInfoArgs;
struct GetDynamicsInfoArgs m_getDynamicsInfoArgs;
struct InitPoseArgs m_initPoseArgs;
struct SendPhysicsSimulationParameters m_physSimParamArgs;
struct BulletDataStreamArgs m_dataStreamArguments;
@@ -839,7 +839,7 @@ struct SharedMemoryStatus
struct StateLoggingResultArgs m_stateLoggingResultArgs;
struct b3OpenGLVisualizerCameraInfo m_visualizerCameraResultArgs;
struct b3ObjectArgs m_removeObjectArgs;
struct b3DynamicInfo m_dynamicInfo;
struct b3DynamicsInfo m_dynamicsInfo;
};
};

View File

@@ -56,8 +56,8 @@ enum EnumSharedMemoryClientCommand
CMD_REQUEST_KEYBOARD_EVENTS_DATA,
CMD_REQUEST_OPENGL_VISUALIZER_CAMERA,
CMD_REMOVE_BODY,
CMD_RESET_DYNAMIC_INFO,
CMD_GET_DYNAMIC_INFO,
CMD_RESET_DYNAMICS_INFO,
CMD_GET_DYNAMICS_INFO,
CMD_PROFILE_TIMING,
//don't go beyond this command!
CMD_MAX_CLIENT_COMMANDS,
@@ -142,8 +142,8 @@ enum EnumSharedMemoryServerStatus
CMD_REQUEST_OPENGL_VISUALIZER_CAMERA_COMPLETED,
CMD_REMOVE_BODY_COMPLETED,
CMD_REMOVE_BODY_FAILED,
CMD_GET_DYNAMIC_INFO_COMPLETED,
CMD_GET_DYNAMIC_INFO_FAILED,
CMD_GET_DYNAMICS_INFO_COMPLETED,
CMD_GET_DYNAMICS_INFO_FAILED,
//don't go beyond 'CMD_MAX_SERVER_COMMANDS!
CMD_MAX_SERVER_COMMANDS
};
@@ -223,7 +223,7 @@ struct b3BodyInfo
const char* m_bodyName; // for btRigidBody, it does not have a base, but can still have a body name from urdf
};
struct b3DynamicInfo
struct b3DynamicsInfo
{
double m_mass;
double m_localInertialPosition[3];

View File

@@ -3,21 +3,20 @@ import time
import math
p.connect(p.GUI)
p.loadURDF(fileName="plane.urdf",baseOrientation=[0.25882,0,0,0.96593])
planeId = p.loadURDF(fileName="plane.urdf",baseOrientation=[0.25882,0,0,0.96593])
p.loadURDF(fileName="cube.urdf",baseOrientation=[0.25882,0,0,0.96593],basePosition=[0,0,2])
p.loadURDF(fileName="cube.urdf",baseOrientation=[0,0,0,1],basePosition=[0,0,4])
p.resetDynamicInfo(bodyUniqueId=2,linkIndex=-1,mass=0.1)
#p.resetDynamicInfo(bodyUniqueId=2,linkIndex=-1,mass=100.0)
cubeId = p.loadURDF(fileName="cube.urdf",baseOrientation=[0,0,0,1],basePosition=[0,0,4])
p.resetDynamicsInfo(bodyUniqueId=2,linkIndex=-1,mass=0.1)
#p.resetDynamicsInfo(bodyUniqueId=2,linkIndex=-1,mass=100.0)
p.setGravity(0,0,-10)
p.setRealTimeSimulation(0)
t=0
while 1:
t=t+1
if t > 400:
p.resetDynamicInfo(bodyUniqueId=0,linkIndex=-1,lateralFriction=0.01)
mass1,frictionCoeff1=p.getDynamicInfo(bodyUniqueId=0,linkIndex=-1)
mass2,frictionCoeff2=p.getDynamicInfo(bodyUniqueId=2,linkIndex=-1)
p.resetDynamicsInfo(bodyUniqueId=0,linkIndex=-1,lateralFriction=0.01)
mass1,frictionCoeff1=p.getDynamicsInfo(bodyUniqueId=planeId,linkIndex=-1)
mass2,frictionCoeff2=p.getDynamicsInfo(bodyUniqueId=cubeId,linkIndex=-1)
print mass1,frictionCoeff1
print mass2,frictionCoeff2
time.sleep(.01)

View File

@@ -604,7 +604,7 @@ static PyObject* pybullet_loadMJCF(PyObject* self, PyObject* args, PyObject* key
return pylist;
}
static PyObject* pybullet_resetDynamicInfo(PyObject* self, PyObject* args, PyObject* keywds)
static PyObject* pybullet_resetDynamicsInfo(PyObject* self, PyObject* args, PyObject* keywds)
{
int bodyUniqueId = -1;
int linkIndex = -2;
@@ -627,17 +627,17 @@ static PyObject* pybullet_resetDynamicInfo(PyObject* self, PyObject* args, PyObj
}
{
b3SharedMemoryCommandHandle command = b3InitResetDynamicInfo(sm);
b3SharedMemoryCommandHandle command = b3InitResetDynamicsInfo(sm);
b3SharedMemoryStatusHandle statusHandle;
if (mass >= 0)
{
b3ResetDynamicInfoSetMass(command, bodyUniqueId, linkIndex, mass);
b3ResetDynamicsInfoSetMass(command, bodyUniqueId, linkIndex, mass);
}
if (lateralFriction >= 0)
{
b3ResetDynamicInfoSetLateralFriction(command, bodyUniqueId, linkIndex, lateralFriction);
b3ResetDynamicsInfoSetLateralFriction(command, bodyUniqueId, linkIndex, lateralFriction);
}
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
@@ -647,7 +647,7 @@ static PyObject* pybullet_resetDynamicInfo(PyObject* self, PyObject* args, PyObj
return Py_None;
}
static PyObject* pybullet_getDynamicInfo(PyObject* self, PyObject* args, PyObject* keywds)
static PyObject* pybullet_getDynamicsInfo(PyObject* self, PyObject* args, PyObject* keywds)
{
{
int bodyUniqueId = -1;
@@ -673,33 +673,33 @@ static PyObject* pybullet_getDynamicInfo(PyObject* self, PyObject* args, PyObjec
if (bodyUniqueId < 0)
{
PyErr_SetString(SpamError, "getDynamicInfo failed; invalid bodyUniqueId");
PyErr_SetString(SpamError, "getDynamicsInfo failed; invalid bodyUniqueId");
return NULL;
}
if (linkIndex < -1)
{
PyErr_SetString(SpamError, "getDynamicInfo failed; invalid linkIndex");
PyErr_SetString(SpamError, "getDynamicsInfo failed; invalid linkIndex");
return NULL;
}
cmd_handle = b3GetDynamicInfoCommandInit(sm, bodyUniqueId, linkIndex);
cmd_handle = b3GetDynamicsInfoCommandInit(sm, bodyUniqueId, linkIndex);
status_handle = b3SubmitClientCommandAndWaitStatus(sm, cmd_handle);
status_type = b3GetStatusType(status_handle);
if (status_type != CMD_GET_DYNAMIC_INFO_COMPLETED)
if (status_type != CMD_GET_DYNAMICS_INFO_COMPLETED)
{
PyErr_SetString(SpamError, "getDynamicInfo failed; invalid return status");
PyErr_SetString(SpamError, "getDynamicsInfo failed; invalid return status");
return NULL;
}
struct b3DynamicInfo info;
if (b3GetDynamicInfo(status_handle, &info))
struct b3DynamicsInfo info;
if (b3GetDynamicsInfo(status_handle, &info))
{
PyObject* pyDynamicInfo = PyTuple_New(2);
PyTuple_SetItem(pyDynamicInfo, 0, PyFloat_FromDouble(info.m_mass));
PyTuple_SetItem(pyDynamicInfo, 1, PyFloat_FromDouble(info.m_lateralFrictionCoeff));
return pyDynamicInfo;
PyObject* pyDynamicsInfo = PyTuple_New(2);
PyTuple_SetItem(pyDynamicsInfo, 0, PyFloat_FromDouble(info.m_mass));
PyTuple_SetItem(pyDynamicsInfo, 1, PyFloat_FromDouble(info.m_lateralFrictionCoeff));
return pyDynamicsInfo;
}
}
}
PyErr_SetString(SpamError, "Couldn't get dynamic info");
PyErr_SetString(SpamError, "Couldn't get dynamics info");
return NULL;
}
@@ -5639,11 +5639,11 @@ static PyMethodDef SpamMethods[] = {
"Reset the state (position, velocity etc) for a joint on a body "
"instantaneously, not through physics simulation."},
{"resetDynamicInfo", (PyCFunction)pybullet_resetDynamicInfo, METH_VARARGS | METH_KEYWORDS,
"Reset dynamic information such as mass, lateral friction coefficient."},
{"resetDynamicsInfo", (PyCFunction)pybullet_resetDynamicsInfo, METH_VARARGS | METH_KEYWORDS,
"Reset dynamics information such as mass, lateral friction coefficient."},
{"getDynamicInfo", (PyCFunction)pybullet_getDynamicInfo, METH_VARARGS | METH_KEYWORDS,
"Get dynamic information such as mass, lateral friction coefficient."},
{"getDynamicsInfo", (PyCFunction)pybullet_getDynamicsInfo, METH_VARARGS | METH_KEYWORDS,
"Get dynamics information such as mass, lateral friction coefficient."},
{"setJointMotorControl", (PyCFunction)pybullet_setJointMotorControl, METH_VARARGS,
"This (obsolete) method cannot select non-zero physicsClientId, use setJointMotorControl2 instead."