Merge pull request #2396 from fuchuyuan/bodytypeAPI
Add body type to dynamics info
This commit is contained in:
@@ -8818,6 +8818,7 @@ bool PhysicsServerCommandProcessor::processGetDynamicsInfoCommand(const struct S
|
|||||||
{
|
{
|
||||||
SharedMemoryStatus& serverCmd = serverStatusOut;
|
SharedMemoryStatus& serverCmd = serverStatusOut;
|
||||||
serverCmd.m_type = CMD_GET_DYNAMICS_INFO_COMPLETED;
|
serverCmd.m_type = CMD_GET_DYNAMICS_INFO_COMPLETED;
|
||||||
|
serverCmd.m_dynamicsInfo.m_bodyType = BT_MULTI_BODY;
|
||||||
|
|
||||||
btMultiBody* mb = body->m_multiBody;
|
btMultiBody* mb = body->m_multiBody;
|
||||||
if (linkIndex == -1)
|
if (linkIndex == -1)
|
||||||
@@ -8932,6 +8933,7 @@ bool PhysicsServerCommandProcessor::processGetDynamicsInfoCommand(const struct S
|
|||||||
{
|
{
|
||||||
SharedMemoryStatus& serverCmd = serverStatusOut;
|
SharedMemoryStatus& serverCmd = serverStatusOut;
|
||||||
serverCmd.m_type = CMD_GET_DYNAMICS_INFO_COMPLETED;
|
serverCmd.m_type = CMD_GET_DYNAMICS_INFO_COMPLETED;
|
||||||
|
serverCmd.m_dynamicsInfo.m_bodyType = BT_RIGID_BODY;
|
||||||
|
|
||||||
btRigidBody* rb = body->m_rigidBody;
|
btRigidBody* rb = body->m_rigidBody;
|
||||||
serverCmd.m_dynamicsInfo.m_lateralFrictionCoeff = rb->getFriction();
|
serverCmd.m_dynamicsInfo.m_lateralFrictionCoeff = rb->getFriction();
|
||||||
@@ -8943,11 +8945,10 @@ bool PhysicsServerCommandProcessor::processGetDynamicsInfoCommand(const struct S
|
|||||||
}
|
}
|
||||||
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
|
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
|
||||||
else if (body && body->m_softBody){
|
else if (body && body->m_softBody){
|
||||||
//todo: @fuchuyuan implement dynamics info
|
SharedMemoryStatus& serverCmd = serverStatusOut;
|
||||||
b3Warning("Softbody dynamics info not set!!!");
|
serverCmd.m_type = CMD_GET_DYNAMICS_INFO_COMPLETED;
|
||||||
SharedMemoryStatus& serverCmd = serverStatusOut;
|
serverCmd.m_dynamicsInfo.m_bodyType = BT_SOFT_BODY;
|
||||||
serverCmd.m_type = CMD_GET_DYNAMICS_INFO_COMPLETED;
|
}
|
||||||
}
|
|
||||||
#endif
|
#endif
|
||||||
return hasStatus;
|
return hasStatus;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -7,7 +7,8 @@
|
|||||||
//Please don't replace an existing magic number:
|
//Please don't replace an existing magic number:
|
||||||
//instead, only ADD a new one at the top, comment-out previous one
|
//instead, only ADD a new one at the top, comment-out previous one
|
||||||
|
|
||||||
#define SHARED_MEMORY_MAGIC_NUMBER 201908110
|
#define SHARED_MEMORY_MAGIC_NUMBER 201909030
|
||||||
|
//#define SHARED_MEMORY_MAGIC_NUMBER 201908110
|
||||||
//#define SHARED_MEMORY_MAGIC_NUMBER 201908050
|
//#define SHARED_MEMORY_MAGIC_NUMBER 201908050
|
||||||
//#define SHARED_MEMORY_MAGIC_NUMBER 2019060190
|
//#define SHARED_MEMORY_MAGIC_NUMBER 2019060190
|
||||||
//#define SHARED_MEMORY_MAGIC_NUMBER 201904030
|
//#define SHARED_MEMORY_MAGIC_NUMBER 201904030
|
||||||
@@ -340,6 +341,13 @@ enum DynamicsActivationState
|
|||||||
eActivationStateDisableWakeup = 32,
|
eActivationStateDisableWakeup = 32,
|
||||||
};
|
};
|
||||||
|
|
||||||
|
enum b3BodyType
|
||||||
|
{
|
||||||
|
BT_RIGID_BODY = 1,
|
||||||
|
BT_MULTI_BODY = 2,
|
||||||
|
BT_SOFT_BODY = 3,
|
||||||
|
};
|
||||||
|
|
||||||
struct b3DynamicsInfo
|
struct b3DynamicsInfo
|
||||||
{
|
{
|
||||||
double m_mass;
|
double m_mass;
|
||||||
@@ -353,6 +361,7 @@ struct b3DynamicsInfo
|
|||||||
double m_contactStiffness;
|
double m_contactStiffness;
|
||||||
double m_contactDamping;
|
double m_contactDamping;
|
||||||
int m_activationState;
|
int m_activationState;
|
||||||
|
int m_bodyType;
|
||||||
double m_angularDamping;
|
double m_angularDamping;
|
||||||
double m_linearDamping;
|
double m_linearDamping;
|
||||||
double m_ccdSweptSphereRadius;
|
double m_ccdSweptSphereRadius;
|
||||||
|
|||||||
@@ -1462,7 +1462,7 @@ static PyObject* pybullet_getDynamicsInfo(PyObject* self, PyObject* args, PyObje
|
|||||||
|
|
||||||
if (b3GetDynamicsInfo(status_handle, &info))
|
if (b3GetDynamicsInfo(status_handle, &info))
|
||||||
{
|
{
|
||||||
int numFields = 10;
|
int numFields = 11;
|
||||||
PyObject* pyDynamicsInfo = PyTuple_New(numFields);
|
PyObject* pyDynamicsInfo = PyTuple_New(numFields);
|
||||||
PyTuple_SetItem(pyDynamicsInfo, 0, PyFloat_FromDouble(info.m_mass));
|
PyTuple_SetItem(pyDynamicsInfo, 0, PyFloat_FromDouble(info.m_mass));
|
||||||
PyTuple_SetItem(pyDynamicsInfo, 1, PyFloat_FromDouble(info.m_lateralFrictionCoeff));
|
PyTuple_SetItem(pyDynamicsInfo, 1, PyFloat_FromDouble(info.m_lateralFrictionCoeff));
|
||||||
@@ -1494,6 +1494,7 @@ static PyObject* pybullet_getDynamicsInfo(PyObject* self, PyObject* args, PyObje
|
|||||||
PyTuple_SetItem(pyDynamicsInfo, 7, PyFloat_FromDouble(info.m_spinningFrictionCoeff));
|
PyTuple_SetItem(pyDynamicsInfo, 7, PyFloat_FromDouble(info.m_spinningFrictionCoeff));
|
||||||
PyTuple_SetItem(pyDynamicsInfo, 8, PyFloat_FromDouble(info.m_contactDamping));
|
PyTuple_SetItem(pyDynamicsInfo, 8, PyFloat_FromDouble(info.m_contactDamping));
|
||||||
PyTuple_SetItem(pyDynamicsInfo, 9, PyFloat_FromDouble(info.m_contactStiffness));
|
PyTuple_SetItem(pyDynamicsInfo, 9, PyFloat_FromDouble(info.m_contactStiffness));
|
||||||
|
PyTuple_SetItem(pyDynamicsInfo, 10, PyInt_FromLong(info.m_bodyType));
|
||||||
return pyDynamicsInfo;
|
return pyDynamicsInfo;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
Reference in New Issue
Block a user