pybullet.getAABB and getAPIVersion
fix btMultiBody::getLinkCollider bump up Bullet C-API version
This commit is contained in:
@@ -4032,6 +4032,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
}
|
||||
int bodyUniqueId = clientCmd.m_requestActualStateInformationCommandArgument.m_bodyUniqueId;
|
||||
InteralBodyData* body = m_data->m_bodyHandles.getHandle(bodyUniqueId);
|
||||
|
||||
|
||||
if (body && body->m_multiBody)
|
||||
{
|
||||
@@ -4040,6 +4041,8 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
serverStatusOut.m_type = CMD_ACTUAL_STATE_UPDATE_COMPLETED;
|
||||
|
||||
serverCmd.m_sendActualStateArgs.m_bodyUniqueId = bodyUniqueId;
|
||||
serverCmd.m_sendActualStateArgs.m_numLinks = body->m_multiBody->getNumLinks();
|
||||
|
||||
int totalDegreeOfFreedomQ = 0;
|
||||
int totalDegreeOfFreedomU = 0;
|
||||
|
||||
@@ -4074,7 +4077,28 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
serverCmd.m_sendActualStateArgs.m_rootLocalInertialFrame[6] =
|
||||
body->m_rootLocalInertialFrame.getRotation()[3];
|
||||
|
||||
serverCmd.m_sendActualStateArgs.m_rootWorldAABBMin[0] = 0;
|
||||
serverCmd.m_sendActualStateArgs.m_rootWorldAABBMin[1] = 0;
|
||||
serverCmd.m_sendActualStateArgs.m_rootWorldAABBMin[2] = 0;
|
||||
|
||||
serverCmd.m_sendActualStateArgs.m_rootWorldAABBMax[0] = -1;
|
||||
serverCmd.m_sendActualStateArgs.m_rootWorldAABBMax[1] = -1;
|
||||
serverCmd.m_sendActualStateArgs.m_rootWorldAABBMax[2] = -1;
|
||||
|
||||
|
||||
|
||||
if (body->m_multiBody->getBaseCollider())
|
||||
{
|
||||
btVector3 aabbMin,aabbMax;
|
||||
body->m_multiBody->getBaseCollider()->getCollisionShape()->getAabb(tr,aabbMin,aabbMax);
|
||||
serverCmd.m_sendActualStateArgs.m_rootWorldAABBMin[0] = aabbMin[0];
|
||||
serverCmd.m_sendActualStateArgs.m_rootWorldAABBMin[1] = aabbMin[1];
|
||||
serverCmd.m_sendActualStateArgs.m_rootWorldAABBMin[2] = aabbMin[2];
|
||||
|
||||
serverCmd.m_sendActualStateArgs.m_rootWorldAABBMax[0] = aabbMax[0];
|
||||
serverCmd.m_sendActualStateArgs.m_rootWorldAABBMax[1] = aabbMax[1];
|
||||
serverCmd.m_sendActualStateArgs.m_rootWorldAABBMax[2] = aabbMax[2];
|
||||
}
|
||||
|
||||
//base position in world space, carthesian
|
||||
serverCmd.m_sendActualStateArgs.m_actualStateQ[0] = tr.getOrigin()[0];
|
||||
@@ -4176,6 +4200,29 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
serverCmd.m_sendActualStateArgs.m_linkState[l*7+5] = linkCOMRotation.z();
|
||||
serverCmd.m_sendActualStateArgs.m_linkState[l*7+6] = linkCOMRotation.w();
|
||||
|
||||
serverCmd.m_sendActualStateArgs.m_linkWorldAABBsMin[3*l+0] = 0;
|
||||
serverCmd.m_sendActualStateArgs.m_linkWorldAABBsMin[3*l+1] = 0;
|
||||
serverCmd.m_sendActualStateArgs.m_linkWorldAABBsMin[3*l+2] = 0;
|
||||
|
||||
serverCmd.m_sendActualStateArgs.m_linkWorldAABBsMax[3*l+0] = -1;
|
||||
serverCmd.m_sendActualStateArgs.m_linkWorldAABBsMax[3*l+1] = -1;
|
||||
serverCmd.m_sendActualStateArgs.m_linkWorldAABBsMax[3*l+2] = -1;
|
||||
|
||||
|
||||
|
||||
if (body->m_multiBody->getLink(l).m_collider)
|
||||
{
|
||||
btVector3 aabbMin,aabbMax;
|
||||
body->m_multiBody->getLinkCollider(l)->getCollisionShape()->getAabb(mb->getLink(l).m_cachedWorldTransform,aabbMin,aabbMax);
|
||||
|
||||
serverCmd.m_sendActualStateArgs.m_linkWorldAABBsMin[3*l+0] = aabbMin[0];
|
||||
serverCmd.m_sendActualStateArgs.m_linkWorldAABBsMin[3*l+1] = aabbMin[1];
|
||||
serverCmd.m_sendActualStateArgs.m_linkWorldAABBsMin[3*l+2] = aabbMin[2];
|
||||
serverCmd.m_sendActualStateArgs.m_linkWorldAABBsMax[3*l+0] = aabbMax[0];
|
||||
serverCmd.m_sendActualStateArgs.m_linkWorldAABBsMax[3*l+1] = aabbMax[1];
|
||||
serverCmd.m_sendActualStateArgs.m_linkWorldAABBsMax[3*l+2] = aabbMax[2];
|
||||
}
|
||||
|
||||
|
||||
btVector3 worldLinVel(0,0,0);
|
||||
btVector3 worldAngVel(0,0,0);
|
||||
@@ -4220,6 +4267,8 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
serverCmd.m_type = CMD_ACTUAL_STATE_UPDATE_COMPLETED;
|
||||
|
||||
serverCmd.m_sendActualStateArgs.m_bodyUniqueId = bodyUniqueId;
|
||||
serverCmd.m_sendActualStateArgs.m_numLinks = 0;
|
||||
|
||||
int totalDegreeOfFreedomQ = 0;
|
||||
int totalDegreeOfFreedomU = 0;
|
||||
|
||||
|
||||
Reference in New Issue
Block a user