mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-14 22:00:05 +00:00
Revert "Create a new pointer in btCollisionShape instead of just using userPtr."
This reverts commit d2d987a5ed
.
After discussion, we decided to use userPtr.
This commit is contained in:
parent
d2d987a5ed
commit
817fb40fb5
@ -1291,8 +1291,8 @@ void OpenGLGuiHelper::computeSoftBodyVertices(btCollisionShape* collisionShape,
|
||||
btAlignedObjectArray<GLInstanceVertex>& gfxVertices,
|
||||
btAlignedObjectArray<int>& indices)
|
||||
{
|
||||
b3Assert(collisionShape->getBodyPointer());
|
||||
btSoftBody* psb = (btSoftBody*)collisionShape->getBodyPointer();
|
||||
b3Assert(collisionShape->getUserPointer());
|
||||
btSoftBody* psb = (btSoftBody*)collisionShape->getUserPointer();
|
||||
gfxVertices.resize(psb->m_faces.size() * 3);
|
||||
int i, j, k;
|
||||
for (i = 0; i < psb->m_faces.size(); i++) // Foreach face
|
||||
|
@ -5862,7 +5862,7 @@ bool PhysicsServerCommandProcessor::processLoadSoftBodyCommand(const struct Shar
|
||||
psb->scale(btVector3(scale,scale,scale));
|
||||
psb->setTotalMass(mass,true);
|
||||
psb->getCollisionShape()->setMargin(collisionMargin);
|
||||
psb->getCollisionShape()->setBodyPointer(psb);
|
||||
psb->getCollisionShape()->setUserPointer(psb);
|
||||
m_data->m_dynamicsWorld->addSoftBody(psb);
|
||||
m_data->m_guiHelper->createCollisionShapeGraphicsObject(psb->getCollisionShape());
|
||||
m_data->m_guiHelper->autogenerateGraphicsObjects(this->m_data->m_dynamicsWorld);
|
||||
|
@ -30,7 +30,6 @@ protected:
|
||||
int m_shapeType;
|
||||
void* m_userPointer;
|
||||
int m_userIndex;
|
||||
void* m_bodyPointer;
|
||||
|
||||
public:
|
||||
|
||||
@ -132,18 +131,6 @@ public:
|
||||
{
|
||||
return m_userPointer;
|
||||
}
|
||||
|
||||
/// optional pointer to body the shape represents
|
||||
void setBodyPointer(void* bodyPointer)
|
||||
{
|
||||
m_bodyPointer = bodyPointer;
|
||||
}
|
||||
|
||||
void* getBodyPointer() const
|
||||
{
|
||||
return m_bodyPointer;
|
||||
}
|
||||
|
||||
void setUserIndex(int index)
|
||||
{
|
||||
m_userIndex = index;
|
||||
|
Loading…
Reference in New Issue
Block a user