add body type info to dynamics info

This commit is contained in:
Chuyuan Fu
2019-09-03 14:27:19 -07:00
parent 25cc1fa386
commit e4a5f9e06e
4 changed files with 24 additions and 8 deletions

View File

@@ -8818,7 +8818,8 @@ bool PhysicsServerCommandProcessor::processGetDynamicsInfoCommand(const struct S
{
SharedMemoryStatus& serverCmd = serverStatusOut;
serverCmd.m_type = CMD_GET_DYNAMICS_INFO_COMPLETED;
serverCmd.m_dynamicsInfo.m_bodyType = BT_MULTI_BODY;
btMultiBody* mb = body->m_multiBody;
if (linkIndex == -1)
{
@@ -8932,6 +8933,7 @@ bool PhysicsServerCommandProcessor::processGetDynamicsInfoCommand(const struct S
{
SharedMemoryStatus& serverCmd = serverStatusOut;
serverCmd.m_type = CMD_GET_DYNAMICS_INFO_COMPLETED;
serverCmd.m_dynamicsInfo.m_bodyType = BT_RIGID_BODY;
btRigidBody* rb = body->m_rigidBody;
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
else if (body && body->m_softBody){
//todo: @fuchuyuan implement dynamics info
b3Warning("Softbody dynamics info not set!!!");
SharedMemoryStatus& serverCmd = serverStatusOut;
serverCmd.m_type = CMD_GET_DYNAMICS_INFO_COMPLETED;
}
SharedMemoryStatus& serverCmd = serverStatusOut;
serverCmd.m_type = CMD_GET_DYNAMICS_INFO_COMPLETED;
serverCmd.m_dynamicsInfo.m_bodyType = BT_SOFT_BODY;
}
#endif
return hasStatus;
}

View File

@@ -7,7 +7,8 @@
//Please don't replace an existing magic number:
//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 2019060190
//#define SHARED_MEMORY_MAGIC_NUMBER 201904030
@@ -340,6 +341,13 @@ enum DynamicsActivationState
eActivationStateDisableWakeup = 32,
};
enum b3BodyType
{
BT_RIGID_BODY = 1,
BT_MULTI_BODY = 2,
BT_SOFT_BODY = 3,
};
struct b3DynamicsInfo
{
double m_mass;
@@ -353,6 +361,7 @@ struct b3DynamicsInfo
double m_contactStiffness;
double m_contactDamping;
int m_activationState;
int m_bodyType;
double m_angularDamping;
double m_linearDamping;
double m_ccdSweptSphereRadius;

View File

@@ -5,6 +5,7 @@ physicsClient = p.connect(p.DIRECT)
p.setGravity(0, 0, -10)
planeId = p.loadURDF("plane.urdf")
boxId = p.loadURDF("cube.urdf", useMaximalCoordinates = True)
bunnyId = p.loadSoftBody("bunny.obj")
#meshData = p.getMeshData(bunnyId)
#print("meshData=",meshData)
@@ -14,6 +15,10 @@ useRealTimeSimulation = 1
if (useRealTimeSimulation):
p.setRealTimeSimulation(1)
print(p.getDynamicsInfo(planeId, -1))
print(p.getDynamicsInfo(bunnyId, 0))
print(p.getDynamicsInfo(boxId, -1))
while p.isConnected():
p.setGravity(0, 0, -10)
if (useRealTimeSimulation):

View File

@@ -1462,7 +1462,7 @@ static PyObject* pybullet_getDynamicsInfo(PyObject* self, PyObject* args, PyObje
if (b3GetDynamicsInfo(status_handle, &info))
{
int numFields = 10;
int numFields = 11;
PyObject* pyDynamicsInfo = PyTuple_New(numFields);
PyTuple_SetItem(pyDynamicsInfo, 0, PyFloat_FromDouble(info.m_mass));
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, 8, PyFloat_FromDouble(info.m_contactDamping));
PyTuple_SetItem(pyDynamicsInfo, 9, PyFloat_FromDouble(info.m_contactStiffness));
PyTuple_SetItem(pyDynamicsInfo, 10, PyInt_FromLong(info.m_bodyType));
return pyDynamicsInfo;
}
}