PyBullet: expose flags to createMultiBody

This commit is contained in:
erwincoumans
2018-06-02 11:37:14 -07:00
parent 39c9ffa4c3
commit cb6b7a7c38
5 changed files with 43 additions and 14 deletions

View File

@@ -1414,6 +1414,20 @@ B3_SHARED_API void b3CreateMultiBodyUseMaximalCoordinates(b3SharedMemoryCommandH
}
}
B3_SHARED_API void b3CreateMultiBodySetFlags(b3SharedMemoryCommandHandle commandHandle, int flags)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command);
b3Assert(command->m_type == CMD_CREATE_MULTI_BODY);
if (command->m_type==CMD_CREATE_MULTI_BODY)
{
command->m_updateFlags |= MULT_BODY_HAS_FLAGS;
command->m_createMultiBodyArgs.m_flags = flags;
}
}
B3_SHARED_API int b3GetStatusMultiBodyUniqueId(b3SharedMemoryStatusHandle statusHandle)
{
const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle;

View File

@@ -466,6 +466,8 @@ B3_SHARED_API int b3CreateMultiBodyLink(b3SharedMemoryCommandHandle commandHandl
//useMaximalCoordinates are disabled by default, enabling them is experimental and not fully supported yet
B3_SHARED_API void b3CreateMultiBodyUseMaximalCoordinates(b3SharedMemoryCommandHandle commandHandle);
B3_SHARED_API void b3CreateMultiBodySetFlags(b3SharedMemoryCommandHandle commandHandle, int flags);
//int b3CreateMultiBodyAddLink(b3SharedMemoryCommandHandle commandHandle, int jointType, int parentLinkIndex, double linkMass, int linkCollisionShapeUnique, int linkVisualShapeUniqueId);

View File

@@ -5804,6 +5804,12 @@ bool PhysicsServerCommandProcessor::processCreateMultiBodyCommand(const struct S
}
int flags = 0;
if (clientCmd.m_updateFlags & MULT_BODY_HAS_FLAGS)
{
flags = clientCmd.m_createMultiBodyArgs.m_flags;
}
bool ok = processImportedObjects("memory", bufferServerToClient, bufferSizeInBytes, useMultiBody, flags, u2b);
if (ok)

View File

@@ -926,6 +926,7 @@ enum eCreateMultiBodyEnum
{
MULTI_BODY_HAS_BASE=1,
MULT_BODY_USE_MAXIMAL_COORDINATES=2,
MULT_BODY_HAS_FLAGS=4,
};
struct b3CreateMultiBodyArgs
{
@@ -947,7 +948,7 @@ struct b3CreateMultiBodyArgs
int m_linkParentIndices[MAX_CREATE_MULTI_BODY_LINKS];
int m_linkJointTypes[MAX_CREATE_MULTI_BODY_LINKS];
double m_linkJointAxis[3*MAX_CREATE_MULTI_BODY_LINKS];
int m_flags;
#if 0
std::string m_name;
std::string m_sourceFile;

View File

@@ -6485,6 +6485,7 @@ static PyObject* pybullet_createMultiBody(PyObject* self, PyObject* args, PyObje
int baseCollisionShapeIndex=-1;
int baseVisualShapeIndex=-1;
int useMaximalCoordinates = 0;
int flags = -1;
PyObject* basePosObj=0;
PyObject* baseOrnObj=0;
PyObject* baseInertialFramePositionObj=0;
@@ -6500,21 +6501,22 @@ static PyObject* pybullet_createMultiBody(PyObject* self, PyObject* args, PyObje
PyObject* linkJointAxisObj=0;
PyObject* linkInertialFramePositionObj=0;
PyObject* linkInertialFrameOrientationObj=0;
static char* kwlist[] = {
"baseMass","baseCollisionShapeIndex","baseVisualShapeIndex","basePosition", "baseOrientation",
"baseInertialFramePosition", "baseInertialFrameOrientation", "linkMasses","linkCollisionShapeIndices",
"linkVisualShapeIndices","linkPositions", "linkOrientations","linkInertialFramePositions","linkInertialFrameOrientations", "linkParentIndices",
"linkJointTypes","linkJointAxis", "useMaximalCoordinates", "flags", "physicsClientId", NULL};
static char* kwlist[] = {"baseMass","baseCollisionShapeIndex","baseVisualShapeIndex","basePosition", "baseOrientation", "baseInertialFramePosition", "baseInertialFrameOrientation",
"linkMasses","linkCollisionShapeIndices", "linkVisualShapeIndices",
"linkPositions", "linkOrientations","linkInertialFramePositions","linkInertialFrameOrientations", "linkParentIndices", "linkJointTypes","linkJointAxis",
"useMaximalCoordinates","physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diiOOOOOOOOOOOOOOii", kwlist, &baseMass,&baseCollisionShapeIndex,&baseVisualShapeIndex,
&basePosObj, &baseOrnObj,&baseInertialFramePositionObj, &baseInertialFrameOrientationObj,
&linkMassesObj, &linkCollisionShapeIndicesObj, &linkVisualShapeIndicesObj, &linkPositionsObj, &linkOrientationsObj,
&linkInertialFramePositionObj, &linkInertialFrameOrientationObj,
&linkParentIndicesObj, &linkJointTypesObj,&linkJointAxisObj,
&useMaximalCoordinates, &physicsClientId))
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diiOOOOOOOOOOOOOOiii", kwlist,
&baseMass,&baseCollisionShapeIndex,&baseVisualShapeIndex,&basePosObj, &baseOrnObj,
&baseInertialFramePositionObj, &baseInertialFrameOrientationObj,&linkMassesObj, &linkCollisionShapeIndicesObj,
&linkVisualShapeIndicesObj, &linkPositionsObj, &linkOrientationsObj,&linkInertialFramePositionObj, &linkInertialFrameOrientationObj,&linkParentIndicesObj,
&linkJointTypesObj,&linkJointAxisObj, &useMaximalCoordinates, &flags, &physicsClientId))
{
return NULL;
}
sm = getPhysicsClient(physicsClientId);
if (sm == 0)
{
@@ -6634,6 +6636,10 @@ static PyObject* pybullet_createMultiBody(PyObject* self, PyObject* args, PyObje
{
b3CreateMultiBodyUseMaximalCoordinates(commandHandle);
}
if (flags >0)
{
b3CreateMultiBodySetFlags(commandHandle, flags);
}
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
statusType = b3GetStatusType(statusHandle);
if (statusType == CMD_CREATE_MULTI_BODY_COMPLETED)
@@ -8172,12 +8178,12 @@ static PyObject* pybullet_calculateInverseKinematics(PyObject* self,
}
else
{
int szInBytes = sizeof(double) * szJointDamping;
int i;
if (szJointDamping != dofCount)
{
printf("calculateInverseKinematics: the size of input joint damping values should be equal to the number of degrees of freedom, ignoring the additonal values.");
}
int szInBytes = sizeof(double) * szJointDamping;
int i;
jointDamping = (double*)malloc(szInBytes);
for (i = 0; i < szJointDamping; i++)
{