Merge pull request #866 from erwincoumans/master
separate 'getClosestPointsAlgorithm', various pybullet improvements
This commit is contained in:
@@ -1167,7 +1167,7 @@ void OpenGLExampleBrowser::update(float deltaTime)
|
||||
}
|
||||
BT_PROFILE("Render Scene");
|
||||
sCurrentDemo->renderScene();
|
||||
}
|
||||
} else
|
||||
{
|
||||
B3_PROFILE("physicsDebugDraw");
|
||||
glPolygonMode( GL_FRONT_AND_BACK, GL_FILL );
|
||||
|
||||
@@ -1515,6 +1515,8 @@ b3SharedMemoryCommandHandle b3InitRequestContactPointInformation(b3PhysicsClient
|
||||
command->m_requestContactPointArguments.m_startingContactPointIndex = 0;
|
||||
command->m_requestContactPointArguments.m_objectAIndexFilter = -1;
|
||||
command->m_requestContactPointArguments.m_objectBIndexFilter = -1;
|
||||
command->m_requestContactPointArguments.m_linkIndexAIndexFilter = -2;
|
||||
command->m_requestContactPointArguments.m_linkIndexBIndexFilter = -2;
|
||||
command->m_updateFlags = 0;
|
||||
return (b3SharedMemoryCommandHandle) command;
|
||||
}
|
||||
@@ -1527,6 +1529,37 @@ void b3SetContactFilterBodyA(b3SharedMemoryCommandHandle commandHandle, int body
|
||||
command->m_requestContactPointArguments.m_objectAIndexFilter = bodyUniqueIdA;
|
||||
}
|
||||
|
||||
void b3SetContactFilterLinkA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_REQUEST_CONTACT_POINT_INFORMATION);
|
||||
command->m_updateFlags |= CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_A_FILTER;
|
||||
command->m_requestContactPointArguments.m_linkIndexAIndexFilter= linkIndexA;
|
||||
}
|
||||
|
||||
void b3SetContactFilterLinkB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_REQUEST_CONTACT_POINT_INFORMATION);
|
||||
command->m_updateFlags |= CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_B_FILTER;
|
||||
command->m_requestContactPointArguments.m_linkIndexBIndexFilter = linkIndexB;
|
||||
}
|
||||
|
||||
void b3SetClosestDistanceFilterLinkA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA)
|
||||
{
|
||||
b3SetContactFilterLinkA(commandHandle, linkIndexA);
|
||||
}
|
||||
|
||||
void b3SetClosestDistanceFilterLinkB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB)
|
||||
{
|
||||
b3SetContactFilterLinkB(commandHandle, linkIndexB);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
void b3SetContactFilterBodyB(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdB)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
|
||||
@@ -124,12 +124,16 @@ void b3RequestCameraImageSetFOVProjectionMatrix(b3SharedMemoryCommandHandle comm
|
||||
b3SharedMemoryCommandHandle b3InitRequestContactPointInformation(b3PhysicsClientHandle physClient);
|
||||
void b3SetContactFilterBodyA(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdA);
|
||||
void b3SetContactFilterBodyB(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdB);
|
||||
void b3SetContactFilterLinkA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA);
|
||||
void b3SetContactFilterLinkB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB);
|
||||
void b3GetContactPointInformation(b3PhysicsClientHandle physClient, struct b3ContactInformation* contactPointInfo);
|
||||
|
||||
///compute the closest points between two bodies
|
||||
b3SharedMemoryCommandHandle b3InitClosestDistanceQuery(b3PhysicsClientHandle physClient);
|
||||
void b3SetClosestDistanceFilterBodyA(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdA);
|
||||
void b3SetClosestDistanceFilterLinkA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA);
|
||||
void b3SetClosestDistanceFilterBodyB(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdB);
|
||||
void b3SetClosestDistanceFilterLinkB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB);
|
||||
void b3SetClosestDistanceThreshold(b3SharedMemoryCommandHandle commandHandle, double distance);
|
||||
void b3GetClosestPointInformation(b3PhysicsClientHandle physClient, struct b3ContactInformation* contactPointInfo);
|
||||
|
||||
|
||||
@@ -542,7 +542,7 @@ struct PhysicsServerCommandProcessorInternalData
|
||||
m_kukaGripperMultiBody(0),
|
||||
m_kukaGripperRevolute1(0),
|
||||
m_kukaGripperRevolute2(0),
|
||||
m_allowRealTimeSimulation(true),
|
||||
m_allowRealTimeSimulation(false),
|
||||
m_huskyId(-1),
|
||||
m_KukaId(-1),
|
||||
m_sphereId(-1),
|
||||
@@ -2774,6 +2774,12 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
int bodyUniqueIdA = clientCmd.m_requestContactPointArguments.m_objectAIndexFilter;
|
||||
int bodyUniqueIdB = clientCmd.m_requestContactPointArguments.m_objectBIndexFilter;
|
||||
|
||||
bool hasLinkIndexAFilter = (0!=(clientCmd.m_updateFlags & CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_A_FILTER));
|
||||
bool hasLinkIndexBFilter = (0!=(clientCmd.m_updateFlags & CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_B_FILTER));
|
||||
|
||||
int linkIndexA = clientCmd.m_requestContactPointArguments.m_linkIndexAIndexFilter;
|
||||
int linkIndexB = clientCmd.m_requestContactPointArguments.m_linkIndexBIndexFilter;
|
||||
|
||||
btAlignedObjectArray<btCollisionObject*> setA;
|
||||
btAlignedObjectArray<btCollisionObject*> setB;
|
||||
btAlignedObjectArray<int> setALinkIndex;
|
||||
@@ -2788,15 +2794,21 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
{
|
||||
if (bodyA->m_multiBody->getBaseCollider())
|
||||
{
|
||||
setA.push_back(bodyA->m_multiBody->getBaseCollider());
|
||||
setALinkIndex.push_back(-1);
|
||||
if (!hasLinkIndexAFilter || (linkIndexA == -1))
|
||||
{
|
||||
setA.push_back(bodyA->m_multiBody->getBaseCollider());
|
||||
setALinkIndex.push_back(-1);
|
||||
}
|
||||
}
|
||||
for (int i = 0; i < bodyA->m_multiBody->getNumLinks(); i++)
|
||||
{
|
||||
if (bodyA->m_multiBody->getLink(i).m_collider)
|
||||
{
|
||||
setA.push_back(bodyA->m_multiBody->getLink(i).m_collider);
|
||||
setALinkIndex.push_back(i);
|
||||
if (!hasLinkIndexAFilter || (linkIndexA == i))
|
||||
{
|
||||
setA.push_back(bodyA->m_multiBody->getLink(i).m_collider);
|
||||
setALinkIndex.push_back(i);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -2816,15 +2828,21 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
{
|
||||
if (bodyB->m_multiBody->getBaseCollider())
|
||||
{
|
||||
setB.push_back(bodyB->m_multiBody->getBaseCollider());
|
||||
setBLinkIndex.push_back(-1);
|
||||
if (!hasLinkIndexBFilter || (linkIndexB == -1))
|
||||
{
|
||||
setB.push_back(bodyB->m_multiBody->getBaseCollider());
|
||||
setBLinkIndex.push_back(-1);
|
||||
}
|
||||
}
|
||||
for (int i = 0; i < bodyB->m_multiBody->getNumLinks(); i++)
|
||||
{
|
||||
if (bodyB->m_multiBody->getLink(i).m_collider)
|
||||
{
|
||||
setB.push_back(bodyB->m_multiBody->getLink(i).m_collider);
|
||||
setBLinkIndex.push_back(i);
|
||||
if (!hasLinkIndexBFilter || (linkIndexB ==i))
|
||||
{
|
||||
setB.push_back(bodyB->m_multiBody->getLink(i).m_collider);
|
||||
setBLinkIndex.push_back(i);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -825,6 +825,7 @@ public:
|
||||
virtual bool wantsTermination();
|
||||
virtual bool isConnected();
|
||||
virtual void renderScene();
|
||||
void drawUserDebugLines();
|
||||
virtual void exitPhysics();
|
||||
|
||||
virtual void physicsDebugDraw(int debugFlags);
|
||||
@@ -1353,7 +1354,51 @@ extern int gHuskyId;
|
||||
extern btTransform huskyTr;
|
||||
|
||||
|
||||
void PhysicsServerExample::drawUserDebugLines()
|
||||
{
|
||||
static char line0[1024];
|
||||
static char line1[1024];
|
||||
|
||||
//draw all user-debug-lines
|
||||
|
||||
//add array of lines
|
||||
|
||||
//draw all user- 'text3d' messages
|
||||
if (m_multiThreadedHelper)
|
||||
{
|
||||
|
||||
for (int i = 0; i<m_multiThreadedHelper->m_userDebugLines.size(); i++)
|
||||
{
|
||||
btVector3 from;
|
||||
from.setValue(m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[0],
|
||||
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[1],
|
||||
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[2]);
|
||||
btVector3 toX;
|
||||
toX.setValue(m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[0],
|
||||
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[1],
|
||||
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[2]);
|
||||
|
||||
btVector3 color;
|
||||
color.setValue(m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[0],
|
||||
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[1],
|
||||
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[2]);
|
||||
|
||||
|
||||
m_guiHelper->getAppInterface()->m_renderer->drawLine(from, toX, color, m_multiThreadedHelper->m_userDebugLines[i].m_lineWidth);
|
||||
}
|
||||
|
||||
for (int i = 0; i<m_multiThreadedHelper->m_userDebugText.size(); i++)
|
||||
{
|
||||
m_guiHelper->getAppInterface()->drawText3D(m_multiThreadedHelper->m_userDebugText[i].m_text,
|
||||
m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[0],
|
||||
m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[1],
|
||||
m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[2],
|
||||
m_multiThreadedHelper->m_userDebugText[i].textSize);
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void PhysicsServerExample::renderScene()
|
||||
{
|
||||
@@ -1369,48 +1414,8 @@ void PhysicsServerExample::renderScene()
|
||||
|
||||
|
||||
B3_PROFILE("PhysicsServerExample::RenderScene");
|
||||
static char line0[1024];
|
||||
static char line1[1024];
|
||||
|
||||
//draw all user-debug-lines
|
||||
|
||||
//add array of lines
|
||||
|
||||
//draw all user- 'text3d' messages
|
||||
if (m_multiThreadedHelper)
|
||||
{
|
||||
|
||||
for (int i=0;i<m_multiThreadedHelper->m_userDebugLines.size();i++)
|
||||
{
|
||||
btVector3 from;
|
||||
from.setValue( m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[0],
|
||||
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[1],
|
||||
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[2]);
|
||||
btVector3 toX;
|
||||
toX.setValue( m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[0],
|
||||
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[1],
|
||||
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[2]);
|
||||
|
||||
btVector3 color;
|
||||
color.setValue( m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[0],
|
||||
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[1],
|
||||
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[2]);
|
||||
|
||||
|
||||
m_guiHelper->getAppInterface()->m_renderer->drawLine(from, toX, color, m_multiThreadedHelper->m_userDebugLines[i].m_lineWidth);
|
||||
}
|
||||
|
||||
for (int i=0;i<m_multiThreadedHelper->m_userDebugText.size();i++)
|
||||
{
|
||||
m_guiHelper->getAppInterface()->drawText3D(m_multiThreadedHelper->m_userDebugText[i].m_text,
|
||||
m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[0],
|
||||
m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[1],
|
||||
m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[2],
|
||||
m_multiThreadedHelper->m_userDebugText[i].textSize);
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
drawUserDebugLines();
|
||||
|
||||
if (gEnableRealTimeSimVR)
|
||||
{
|
||||
@@ -1424,6 +1429,7 @@ void PhysicsServerExample::renderScene()
|
||||
static int count = 0;
|
||||
count++;
|
||||
|
||||
#if 0
|
||||
if (0 == (count & 1))
|
||||
{
|
||||
btScalar curTime = m_clock.getTimeSeconds();
|
||||
@@ -1444,6 +1450,7 @@ void PhysicsServerExample::renderScene()
|
||||
worseFps = 1000000;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef BT_ENABLE_VR
|
||||
if ((gInternalSimFlags&2 ) && m_tinyVrGui==0)
|
||||
@@ -1468,7 +1475,9 @@ void PhysicsServerExample::renderScene()
|
||||
tr = tr*b3Transform(b3Quaternion(0,0,-SIMD_HALF_PI),b3MakeVector3(0,0,0));
|
||||
b3Scalar dt = 0.01;
|
||||
m_tinyVrGui->clearTextArea();
|
||||
|
||||
static char line0[1024];
|
||||
static char line1[1024];
|
||||
|
||||
m_tinyVrGui->grapicalPrintf(line0,0,0,0,0,0,255);
|
||||
m_tinyVrGui->grapicalPrintf(line1,0,16,255,255,255,255);
|
||||
|
||||
@@ -1544,6 +1553,8 @@ void PhysicsServerExample::renderScene()
|
||||
|
||||
void PhysicsServerExample::physicsDebugDraw(int debugDrawFlags)
|
||||
{
|
||||
drawUserDebugLines();
|
||||
|
||||
///debug rendering
|
||||
m_physicsServer.physicsDebugDraw(debugDrawFlags);
|
||||
|
||||
|
||||
@@ -156,6 +156,8 @@ enum EnumRequestContactDataUpdateFlags
|
||||
{
|
||||
CMD_REQUEST_CONTACT_POINT_HAS_QUERY_MODE=1,
|
||||
CMD_REQUEST_CONTACT_POINT_HAS_CLOSEST_DISTANCE_THRESHOLD=2,
|
||||
CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_A_FILTER = 4,
|
||||
CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_B_FILTER = 8,
|
||||
};
|
||||
|
||||
struct RequestContactDataArgs
|
||||
@@ -163,6 +165,8 @@ struct RequestContactDataArgs
|
||||
int m_startingContactPointIndex;
|
||||
int m_objectAIndexFilter;
|
||||
int m_objectBIndexFilter;
|
||||
int m_linkIndexAIndexFilter;
|
||||
int m_linkIndexBIndexFilter;
|
||||
double m_closestDistanceThreshold;
|
||||
int m_mode;
|
||||
};
|
||||
|
||||
@@ -1501,7 +1501,7 @@ static PyObject* pybullet_addUserDebugText(PyObject* self, PyObject* args, PyObj
|
||||
res = pybullet_internalSetVectord(textPositionObj,posXYZ);
|
||||
if (!res)
|
||||
{
|
||||
PyErr_SetString(SpamError, "Error converting lineFrom[3]");
|
||||
PyErr_SetString(SpamError, "Error converting textPositionObj[3]");
|
||||
return NULL;
|
||||
}
|
||||
|
||||
@@ -1510,7 +1510,7 @@ static PyObject* pybullet_addUserDebugText(PyObject* self, PyObject* args, PyObj
|
||||
res = pybullet_internalSetVectord(textColorRGBObj,colorRGB);
|
||||
if (!res)
|
||||
{
|
||||
PyErr_SetString(SpamError, "Error converting lineTo[3]");
|
||||
PyErr_SetString(SpamError, "Error converting textColorRGBObj[3]");
|
||||
return NULL;
|
||||
}
|
||||
}
|
||||
@@ -1848,23 +1848,22 @@ static PyObject* MyConvertContactPoint( struct b3ContactInformation* contactPoin
|
||||
2 int m_bodyUniqueIdB;
|
||||
3 int m_linkIndexA;
|
||||
4 int m_linkIndexB;
|
||||
5-6-7 double m_positionOnAInWS[3];//contact point location on object A,
|
||||
5 double m_positionOnAInWS[3];//contact point location on object A,
|
||||
in world space coordinates
|
||||
8-9-10 double m_positionOnBInWS[3];//contact point location on object
|
||||
6 double m_positionOnBInWS[3];//contact point location on object
|
||||
A, in world space coordinates
|
||||
11-12-13 double m_contactNormalOnBInWS[3];//the separating contact
|
||||
7 double m_contactNormalOnBInWS[3];//the separating contact
|
||||
normal, pointing from object B towards object A
|
||||
14 double m_contactDistance;//negative number is penetration, positive
|
||||
8 double m_contactDistance;//negative number is penetration, positive
|
||||
is distance.
|
||||
|
||||
15 double m_normalForce;
|
||||
9 double m_normalForce;
|
||||
*/
|
||||
|
||||
int i;
|
||||
|
||||
PyObject* pyResultList = PyTuple_New(contactPointPtr->m_numContactPoints);
|
||||
for (i = 0; i < contactPointPtr->m_numContactPoints; i++) {
|
||||
PyObject* contactObList = PyTuple_New(16); // see above 16 fields
|
||||
PyObject* contactObList = PyTuple_New(10); // see above 10 fields
|
||||
PyObject* item;
|
||||
item =
|
||||
PyInt_FromLong(contactPointPtr->m_contactPointData[i].m_contactFlags);
|
||||
@@ -1881,42 +1880,61 @@ static PyObject* MyConvertContactPoint( struct b3ContactInformation* contactPoin
|
||||
item =
|
||||
PyInt_FromLong(contactPointPtr->m_contactPointData[i].m_linkIndexB);
|
||||
PyTuple_SetItem(contactObList, 4, item);
|
||||
item = PyFloat_FromDouble(
|
||||
contactPointPtr->m_contactPointData[i].m_positionOnAInWS[0]);
|
||||
PyTuple_SetItem(contactObList, 5, item);
|
||||
item = PyFloat_FromDouble(
|
||||
contactPointPtr->m_contactPointData[i].m_positionOnAInWS[1]);
|
||||
PyTuple_SetItem(contactObList, 6, item);
|
||||
item = PyFloat_FromDouble(
|
||||
contactPointPtr->m_contactPointData[i].m_positionOnAInWS[2]);
|
||||
PyTuple_SetItem(contactObList, 7, item);
|
||||
|
||||
item = PyFloat_FromDouble(
|
||||
contactPointPtr->m_contactPointData[i].m_positionOnBInWS[0]);
|
||||
PyTuple_SetItem(contactObList, 8, item);
|
||||
item = PyFloat_FromDouble(
|
||||
contactPointPtr->m_contactPointData[i].m_positionOnBInWS[1]);
|
||||
PyTuple_SetItem(contactObList, 9, item);
|
||||
item = PyFloat_FromDouble(
|
||||
contactPointPtr->m_contactPointData[i].m_positionOnBInWS[2]);
|
||||
PyTuple_SetItem(contactObList, 10, item);
|
||||
{
|
||||
PyObject* posAObj = PyTuple_New(3);
|
||||
|
||||
item = PyFloat_FromDouble(
|
||||
contactPointPtr->m_contactPointData[i].m_contactNormalOnBInWS[0]);
|
||||
PyTuple_SetItem(contactObList, 11, item);
|
||||
item = PyFloat_FromDouble(
|
||||
contactPointPtr->m_contactPointData[i].m_contactNormalOnBInWS[1]);
|
||||
PyTuple_SetItem(contactObList, 12, item);
|
||||
item = PyFloat_FromDouble(
|
||||
contactPointPtr->m_contactPointData[i].m_contactNormalOnBInWS[2]);
|
||||
PyTuple_SetItem(contactObList, 13, item);
|
||||
item = PyFloat_FromDouble(
|
||||
contactPointPtr->m_contactPointData[i].m_positionOnAInWS[0]);
|
||||
PyTuple_SetItem(posAObj, 0, item);
|
||||
item = PyFloat_FromDouble(
|
||||
contactPointPtr->m_contactPointData[i].m_positionOnAInWS[1]);
|
||||
PyTuple_SetItem(posAObj, 1, item);
|
||||
item = PyFloat_FromDouble(
|
||||
contactPointPtr->m_contactPointData[i].m_positionOnAInWS[2]);
|
||||
PyTuple_SetItem(posAObj, 2, item);
|
||||
|
||||
PyTuple_SetItem(contactObList, 5, posAObj);
|
||||
}
|
||||
|
||||
{
|
||||
PyObject* posBObj = PyTuple_New(3);
|
||||
|
||||
|
||||
item = PyFloat_FromDouble(
|
||||
contactPointPtr->m_contactPointData[i].m_positionOnBInWS[0]);
|
||||
PyTuple_SetItem(posBObj, 0, item);
|
||||
item = PyFloat_FromDouble(
|
||||
contactPointPtr->m_contactPointData[i].m_positionOnBInWS[1]);
|
||||
PyTuple_SetItem(posBObj, 1, item);
|
||||
item = PyFloat_FromDouble(
|
||||
contactPointPtr->m_contactPointData[i].m_positionOnBInWS[2]);
|
||||
PyTuple_SetItem(posBObj, 2, item);
|
||||
|
||||
PyTuple_SetItem(contactObList, 6, posBObj);
|
||||
|
||||
}
|
||||
|
||||
{
|
||||
PyObject* normalOnB = PyTuple_New(3);
|
||||
item = PyFloat_FromDouble(
|
||||
contactPointPtr->m_contactPointData[i].m_contactNormalOnBInWS[0]);
|
||||
PyTuple_SetItem(normalOnB, 0, item);
|
||||
item = PyFloat_FromDouble(
|
||||
contactPointPtr->m_contactPointData[i].m_contactNormalOnBInWS[1]);
|
||||
PyTuple_SetItem(normalOnB, 1, item);
|
||||
item = PyFloat_FromDouble(
|
||||
contactPointPtr->m_contactPointData[i].m_contactNormalOnBInWS[2]);
|
||||
PyTuple_SetItem(normalOnB, 2, item);
|
||||
PyTuple_SetItem(contactObList, 7, normalOnB);
|
||||
}
|
||||
|
||||
item = PyFloat_FromDouble(
|
||||
contactPointPtr->m_contactPointData[i].m_contactDistance);
|
||||
PyTuple_SetItem(contactObList, 14, item);
|
||||
PyTuple_SetItem(contactObList, 8, item);
|
||||
item = PyFloat_FromDouble(
|
||||
contactPointPtr->m_contactPointData[i].m_normalForce);
|
||||
PyTuple_SetItem(contactObList, 15, item);
|
||||
PyTuple_SetItem(contactObList, 9, item);
|
||||
|
||||
PyTuple_SetItem(pyResultList, i, contactObList);
|
||||
}
|
||||
@@ -1982,6 +2000,9 @@ static PyObject* pybullet_getClosestPointData(PyObject* self, PyObject* args, Py
|
||||
int size = PySequence_Size(args);
|
||||
int bodyUniqueIdA = -1;
|
||||
int bodyUniqueIdB = -1;
|
||||
int linkIndexA = -2;
|
||||
int linkIndexB = -2;
|
||||
|
||||
double distanceThreshold = 0.f;
|
||||
|
||||
b3SharedMemoryCommandHandle commandHandle;
|
||||
@@ -1991,15 +2012,15 @@ static PyObject* pybullet_getClosestPointData(PyObject* self, PyObject* args, Py
|
||||
PyObject* pyResultList = 0;
|
||||
|
||||
|
||||
static char *kwlist[] = { "bodyA", "bodyB", "distance", NULL };
|
||||
static char *kwlist[] = { "bodyA", "bodyB", "distance", "linkIndexA","linkIndexB",NULL };
|
||||
|
||||
if (0 == sm) {
|
||||
PyErr_SetString(SpamError, "Not connected to physics server.");
|
||||
return NULL;
|
||||
}
|
||||
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iid", kwlist,
|
||||
&bodyUniqueIdA, &bodyUniqueIdB, &distanceThreshold))
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iid|ii", kwlist,
|
||||
&bodyUniqueIdA, &bodyUniqueIdB, &distanceThreshold, &linkIndexA, &linkIndexB))
|
||||
return NULL;
|
||||
|
||||
|
||||
@@ -2007,7 +2028,14 @@ static PyObject* pybullet_getClosestPointData(PyObject* self, PyObject* args, Py
|
||||
b3SetClosestDistanceFilterBodyA(commandHandle, bodyUniqueIdA);
|
||||
b3SetClosestDistanceFilterBodyB(commandHandle, bodyUniqueIdB);
|
||||
b3SetClosestDistanceThreshold(commandHandle, distanceThreshold);
|
||||
|
||||
if (linkIndexA >= -1)
|
||||
{
|
||||
b3SetClosestDistanceFilterLinkA(commandHandle, linkIndexA);
|
||||
}
|
||||
if (linkIndexB >= -1)
|
||||
{
|
||||
b3SetClosestDistanceFilterLinkB(commandHandle, linkIndexB);
|
||||
}
|
||||
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
|
||||
Reference in New Issue
Block a user