Merge branch 'master' of github.com:erwincoumans/bullet3

This commit is contained in:
Erwin Coumans 2020-09-11 18:05:15 -07:00
commit b097753dc4
50 changed files with 8329 additions and 293 deletions

11
data/ball.mtl Normal file
View File

@ -0,0 +1,11 @@
# Blender MTL File: 'None'
# Material Count: 1
newmtl None
Ns 0
Ka 0.000000 0.000000 0.000000
Kd 0.8 0.8 0.8
Ks 0.8 0.8 0.8
d 1
illum 2
map_Kd uvmap.png

1722
data/ball.obj Normal file

File diff suppressed because it is too large Load Diff

11
data/banana.mtl Normal file
View File

@ -0,0 +1,11 @@
# Blender MTL File: 'None'
# Material Count: 1
newmtl None
Ns 0
Ka 0.000000 0.000000 0.000000
Kd 0.8 0.8 0.8
Ks 0.8 0.8 0.8
d 1
illum 2
map_Kd banana.png

3310
data/banana.obj Normal file

File diff suppressed because it is too large Load Diff

BIN
data/banana.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 114 KiB

13
data/cloth_z_up.mtl Normal file
View File

@ -0,0 +1,13 @@
# Blender MTL File: 'None'
# Material Count: 1
newmtl None
Ns 94.117647
Ka 1.000000 1.000000 1.000000
Kd 0.640000 0.640000 0.640000
Ks 0.500000 0.500000 0.500000
Ke 0.000000 0.000000 0.000000
Ni 1.000000
d 1.000000
illum 2
map_Kd cube.png

View File

@ -2,63 +2,88 @@
# www.blender.org
mtllib cloth_z_up.mtl
o Plane_Plane.001
v -1.000000 -1.000000 0.000000
v 1.000000 -1.000000 0.000000
v -1.000000 1.000000 -0.000000
v 1.000000 1.000000 -0.000000
v -1.000000 0.000000 0.000000
v -0.000000 -1.000000 0.000000
v 1.000000 -0.000000 -0.000000
v 0.000000 1.000000 -0.000000
v 1.000000 -0.500000 -0.000000
v 0.500000 -1.000000 -0.000000
v 0.500000 -0.500000 -0.000000
v 0.000000 -0.500000 -0.000000
v -0.500000 -1.000000 -0.000000
v -0.500000 -0.500000 -0.000000
v -0.000000 0.500000 0.000000
v -0.500000 0.000000 -0.000000
v -0.500000 0.500000 0.000000
v 1.000000 0.500000 0.000000
v 0.500000 0.000000 0.000000
v 0.500000 0.500000 0.000000
v 0.000000 0.000000 0.000000
v -1.000000 -0.500000 0.000000
v 0.500000 -1.000000 0.000000
v 1.000000 0.500000 -0.000000
v -0.500000 1.000000 -0.000000
v -1.000000 0.500000 -0.000000
v -0.500000 -1.000000 0.000000
v 1.000000 -0.500000 0.000000
v 0.500000 1.000000 -0.000000
v 0.000000 0.500000 -0.000000
v -0.000000 -0.500000 0.000000
v -0.500000 0.000000 0.000000
v 0.500000 -0.000000 -0.000000
v 0.500000 -0.500000 0.000000
v -0.500000 -0.500000 0.000000
v -0.500000 0.500000 -0.000000
v 0.500000 0.500000 -0.000000
vn 0.0000 0.0000 1.0000
v 0.500000 1.000000 0.000000
v -0.000000 1.000000 0.000000
v 1.000000 1.000000 0.000000
v -1.000000 0.000000 -0.000000
v -1.000000 0.500000 0.000000
v -0.500000 1.000000 0.000000
v -1.000000 1.000000 0.000000
v -1.000000 -1.000000 -0.000000
v -1.000000 -0.500000 -0.000000
v 0.000000 -1.000000 -0.000000
v 1.000000 0.000000 0.000000
v 1.000000 -1.000000 -0.000000
vt 0.976031 1.084981
vt 0.738016 1.669965
vt 0.738016 1.084981
vt 0.499998 1.084981
vt 0.261984 1.669965
vt 0.261984 1.084981
vt 0.499998 -0.084982
vt 0.261984 0.500000
vt 0.261984 -0.084982
vt 0.976031 -0.084982
vt 0.738016 0.500000
vt 0.738016 -0.084982
vt 0.499998 0.500000
vt 0.738016 -0.669965
vt 0.499998 -0.669965
vt 0.976031 -0.669965
vt 0.023969 0.500000
vt 0.023969 -0.084982
vt 0.261984 -0.669965
vt 0.023969 -0.669965
vt 0.023969 1.669965
vt 0.023969 1.084981
vt 0.499998 1.669965
vt 0.976031 0.500000
vt 0.976031 1.669965
vn 0.0000 0.0000 -1.0000
usemtl None
s off
f 12//1 17//1 25//1
f 18//1 13//1 24//1
f 19//1 20//1 23//1
f 16//1 21//1 22//1
f 22//1 9//1 19//1
f 11//1 19//1 6//1
f 2//1 22//1 11//1
f 23//1 5//1 10//1
f 15//1 10//1 1//1
f 6//1 23//1 15//1
f 24//1 3//1 14//1
f 20//1 14//1 5//1
f 9//1 24//1 20//1
f 25//1 8//1 18//1
f 21//1 18//1 9//1
f 7//1 25//1 21//1
f 12//1 4//1 17//1
f 18//1 8//1 13//1
f 19//1 9//1 20//1
f 16//1 7//1 21//1
f 22//1 21//1 9//1
f 11//1 22//1 19//1
f 2//1 16//1 22//1
f 23//1 20//1 5//1
f 15//1 23//1 10//1
f 6//1 19//1 23//1
f 24//1 13//1 3//1
f 20//1 24//1 14//1
f 9//1 18//1 24//1
f 25//1 17//1 8//1
f 21//1 25//1 18//1
f 7//1 12//1 25//1
s 1
f 1/1/1 2/2/1 3/3/1
f 4/4/1 5/5/1 6/6/1
f 7/7/1 8/8/1 9/9/1
f 10/10/1 11/11/1 12/12/1
f 12/12/1 13/13/1 7/7/1
f 14/14/1 7/7/1 15/15/1
f 16/16/1 12/12/1 14/14/1
f 9/9/1 17/17/1 18/18/1
f 19/19/1 18/18/1 20/20/1
f 15/15/1 9/9/1 19/19/1
f 6/6/1 21/21/1 22/22/1
f 8/8/1 22/22/1 17/17/1
f 13/13/1 6/6/1 8/8/1
f 3/3/1 23/23/1 4/4/1
f 11/11/1 4/4/1 13/13/1
f 24/24/1 3/3/1 11/11/1
f 1/1/1 25/25/1 2/2/1
f 4/4/1 23/23/1 5/5/1
f 7/7/1 13/13/1 8/8/1
f 10/10/1 24/24/1 11/11/1
f 12/12/1 11/11/1 13/13/1
f 14/14/1 12/12/1 7/7/1
f 16/16/1 10/10/1 12/12/1
f 9/9/1 8/8/1 17/17/1
f 19/19/1 9/9/1 18/18/1
f 15/15/1 7/7/1 9/9/1
f 6/6/1 5/5/1 21/21/1
f 8/8/1 6/6/1 22/22/1
f 13/13/1 4/4/1 6/6/1
f 3/3/1 2/2/1 23/23/1
f 11/11/1 3/3/1 4/4/1
f 24/24/1 1/1/1 3/3/1

32
data/cloth_z_up.urdf Normal file
View File

@ -0,0 +1,32 @@
<?xml version="1.0" ?>
<robot name="cube">
<link name="baseLink">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="0.0"/>
<contact_cfm value="0.0"/>
<contact_erp value="1.0"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="1.0"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="cloth_z_up.obj" scale="1 1 1"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="1 1 1"/>
</geometry>
</collision>
</link>
</robot>

View File

@ -0,0 +1,11 @@
# Blender MTL File: 'None'
# Material Count: 1
newmtl None
Ns 0
Ka 0.000000 0.000000 0.000000
Kd 0.8 0.8 0.8
Ks 0.8 0.8 0.8
d 1
illum 2
map_Kd ../cube.png

File diff suppressed because it is too large Load Diff

View File

@ -81,7 +81,7 @@ struct CommonRenderInterface
virtual void drawTexturedTriangleMesh(float worldPosition[3], float worldOrientation[4], const float* vertices, int numvertices, const unsigned int* indices, int numIndices, float color[4], int textureIndex = -1, int vertexLayout = 0) = 0;
virtual int registerShape(const float* vertices, int numvertices, const int* indices, int numIndices, int primitiveType = B3_GL_TRIANGLES, int textureIndex = -1) = 0;
virtual void updateShape(int shapeIndex, const float* vertices) = 0;
virtual void updateShape(int shapeIndex, const float* vertices, int numVertices) = 0;
virtual int registerTexture(const unsigned char* texels, int width, int height, bool flipPixelsY = true) = 0;
virtual void updateTexture(int textureIndex, const unsigned char* texels, bool flipPixelsY = true) = 0;

View File

@ -313,6 +313,13 @@ void OpenGLGuiHelper::createCollisionObjectGraphicsObject(btCollisionObject* bod
btVector3 localScaling(1, 1, 1);
int graphicsInstanceId = m_data->m_glApp->m_renderer->registerGraphicsInstance(graphicsShapeId, startTransform.getOrigin(), startTransform.getRotation(), color, localScaling);
body->setUserIndex(graphicsInstanceId);
btSoftBody* sb = btSoftBody::upcast(body);
if (sb)
{
int graphicsInstanceId = body->getUserIndex();
changeInstanceFlags(graphicsInstanceId, B3_INSTANCE_DOUBLE_SIDED);
}
}
}
}
@ -560,8 +567,7 @@ void OpenGLGuiHelper::createCollisionShapeGraphicsObject(btCollisionShape* colli
computeSoftBodyVertices(collisionShape, gfxVertices, indices);
if (gfxVertices.size() && indices.size())
{
int shapeId = registerGraphicsShape(&gfxVertices[0].xyzw[0], gfxVertices.size(), &indices[0], indices.size(), B3_GL_TRIANGLES,
m_data->m_checkedTexture);
int shapeId = registerGraphicsShape(&gfxVertices[0].xyzw[0], gfxVertices.size(), &indices[0], indices.size(), B3_GL_TRIANGLES,m_data->m_checkedTexture);
b3Assert(shapeId >= 0);
collisionShape->setUserIndex(shapeId);
@ -1051,10 +1057,33 @@ void OpenGLGuiHelper::syncPhysicsToGraphics(const btDiscreteDynamicsWorld* rbWor
btCollisionShape* collisionShape = colObj->getCollisionShape();
if (collisionShape->getShapeType() == SOFTBODY_SHAPE_PROXYTYPE && collisionShape->getUserIndex() >= 0)
{
const btSoftBody* psb = (const btSoftBody*)colObj;
btAlignedObjectArray<GLInstanceVertex> gfxVertices;
btAlignedObjectArray<int> indices;
computeSoftBodyVertices(collisionShape, gfxVertices, indices);
m_data->m_glApp->m_renderer->updateShape(collisionShape->getUserIndex(), &gfxVertices[0].xyzw[0]);
if (psb->m_renderNodes.size() > 0)
{
gfxVertices.resize(psb->m_renderNodes.size());
for (int i = 0; i < psb->m_renderNodes.size(); i++) // Foreach face
{
gfxVertices[i].xyzw[0] = psb->m_renderNodes[i].m_x[0];
gfxVertices[i].xyzw[1] = psb->m_renderNodes[i].m_x[1];
gfxVertices[i].xyzw[2] = psb->m_renderNodes[i].m_x[2];
gfxVertices[i].xyzw[3] = psb->m_renderNodes[i].m_x[3];
gfxVertices[i].uv[0] = psb->m_renderNodes[i].m_uv1[0];
gfxVertices[i].uv[1] = psb->m_renderNodes[i].m_uv1[1];
//gfxVertices[i].normal[0] = psb->m_renderNodes[i].
gfxVertices[i].normal[0] = psb->m_renderNodes[i].m_normal[0];
gfxVertices[i].normal[1] = psb->m_renderNodes[i].m_normal[1];
gfxVertices[i].normal[2] = psb->m_renderNodes[i].m_normal[2];
}
}
else
{
btAlignedObjectArray<int> indices;
computeSoftBodyVertices(collisionShape, gfxVertices, indices);
}
m_data->m_glApp->m_renderer->updateShape(collisionShape->getUserIndex(), &gfxVertices[0].xyzw[0], gfxVertices.size());
continue;
}
btVector3 pos = colObj->getWorldTransform().getOrigin();
@ -1449,11 +1478,7 @@ void OpenGLGuiHelper::autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWor
color.setValue(1, 1, 1, 1);
}
createCollisionObjectGraphicsObject(colObj, color);
if (sb)
{
int graphicsInstanceId = colObj->getUserIndex();
changeInstanceFlags(graphicsInstanceId, B3_INSTANCE_DOUBLE_SIDED);
}
}
}
@ -1511,14 +1536,14 @@ void OpenGLGuiHelper::computeSoftBodyVertices(btCollisionShape* collisionShape,
}
for (int j = 0; j < 2; j++)
{
gfxVertices[currentIndex].uv[j] = 0.5; //we don't have UV info...
gfxVertices[currentIndex].uv[j] = psb->m_faces[i].m_n[k]->m_x[j];
}
indices.push_back(currentIndex);
}
}
}
void OpenGLGuiHelper::updateShape(int shapeIndex, float* vertices)
void OpenGLGuiHelper::updateShape(int shapeIndex, float* vertices, int numVertices)
{
m_data->m_glApp->m_renderer->updateShape(shapeIndex, vertices);
m_data->m_glApp->m_renderer->updateShape(shapeIndex, vertices, numVertices);
}

View File

@ -35,7 +35,7 @@ struct OpenGLGuiHelper : public GUIHelperInterface
virtual void removeTexture(int textureUid);
virtual int getShapeIndexFromInstance(int instanceUid);
virtual void replaceTexture(int shapeIndex, int textureUid);
virtual void updateShape(int shapeIndex, float* vertices);
virtual void updateShape(int shapeIndex, float* vertices, int numVertices);
virtual void createCollisionShapeGraphicsObject(btCollisionShape* collisionShape);

View File

@ -25,10 +25,10 @@ files {
"../RenderingExamples/TimeSeriesCanvas.cpp",
"../RenderingExamples/TimeSeriesFontData.cpp",
"../MultiBody/InvertedPendulumPDControl.cpp",
"../ThirdPartyLibs/tinyxml/tinystr.cpp",
"../ThirdPartyLibs/tinyxml/tinyxml.cpp",
"../ThirdPartyLibs/tinyxml/tinyxmlerror.cpp",
"../ThirdPartyLibs/tinyxml/tinyxmlparser.cpp",
"../ThirdPartyLibs/tinyxml2/tinystr.cpp",
"../ThirdPartyLibs/tinyxml2/tinyxml.cpp",
"../ThirdPartyLibs/tinyxml2/tinyxmlerror.cpp",
"../ThirdPartyLibs/tinyxml2/tinyxmlparser.cpp",
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp",
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.h",
"../Importers/ImportColladaDemo/LoadMeshFromCollada.cpp",
@ -78,10 +78,10 @@ files {
"../RenderingExamples/TimeSeriesCanvas.cpp",
"../RenderingExamples/TimeSeriesFontData.cpp",
"../MultiBody/InvertedPendulumPDControl.cpp",
"../ThirdPartyLibs/tinyxml/tinystr.cpp",
"../ThirdPartyLibs/tinyxml/tinyxml.cpp",
"../ThirdPartyLibs/tinyxml/tinyxmlerror.cpp",
"../ThirdPartyLibs/tinyxml/tinyxmlparser.cpp",
"../ThirdPartyLibs/tinyxml2/tinystr.cpp",
"../ThirdPartyLibs/tinyxml2/tinyxml.cpp",
"../ThirdPartyLibs/tinyxml2/tinyxmlerror.cpp",
"../ThirdPartyLibs/tinyxml2/tinyxmlparser.cpp",
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp",
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.h",
"../Importers/ImportColladaDemo/LoadMeshFromCollada.cpp",
@ -146,10 +146,10 @@ files {
"../RenderingExamples/TimeSeriesCanvas.cpp",
"../RenderingExamples/TimeSeriesFontData.cpp",
"../MultiBody/InvertedPendulumPDControl.cpp",
"../ThirdPartyLibs/tinyxml/tinystr.cpp",
"../ThirdPartyLibs/tinyxml/tinyxml.cpp",
"../ThirdPartyLibs/tinyxml/tinyxmlerror.cpp",
"../ThirdPartyLibs/tinyxml/tinyxmlparser.cpp",
"../ThirdPartyLibs/tinyxml2/tinystr.cpp",
"../ThirdPartyLibs/tinyxml2/tinyxml.cpp",
"../ThirdPartyLibs/tinyxml2/tinyxmlerror.cpp",
"../ThirdPartyLibs/tinyxml2/tinyxmlparser.cpp",
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp",
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.h",
"../Importers/ImportColladaDemo/LoadMeshFromCollada.cpp",
@ -208,10 +208,10 @@ files {
"../RenderingExamples/TimeSeriesCanvas.cpp",
"../RenderingExamples/TimeSeriesFontData.cpp",
"../MultiBody/InvertedPendulumPDControl.cpp",
"../ThirdPartyLibs/tinyxml/tinystr.cpp",
"../ThirdPartyLibs/tinyxml/tinyxml.cpp",
"../ThirdPartyLibs/tinyxml/tinyxmlerror.cpp",
"../ThirdPartyLibs/tinyxml/tinyxmlparser.cpp",
"../ThirdPartyLibs/tinyxml2/tinystr.cpp",
"../ThirdPartyLibs/tinyxml2/tinyxml.cpp",
"../ThirdPartyLibs/tinyxml2/tinyxmlerror.cpp",
"../ThirdPartyLibs/tinyxml2/tinyxmlparser.cpp",
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp",
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.h",
"../Importers/ImportColladaDemo/LoadMeshFromCollada.cpp",

View File

@ -1110,7 +1110,7 @@ void HeightfieldExample::stepSimulation(float deltaTime)
m_heightfieldShape->processAllTriangles(&col, aabbMin, aabbMax);
if (gfxVertices.size() && indices.size())
{
m_guiHelper->getRenderInterface()->updateShape(m_heightfieldShape->getUserIndex(), &gfxVertices[0].xyzw[0]);
m_guiHelper->getRenderInterface()->updateShape(m_heightfieldShape->getUserIndex(), &gfxVertices[0].xyzw[0], gfxVertices.size());
}
}

View File

@ -6,6 +6,7 @@ struct UrdfLink;
struct UrdfModel;
///btTransform is a position and 3x3 matrix, as defined in Bullet/src/LinearMath/btTransform
class btTransform;
class btVector3;
///UrdfRenderingInterface is a simple rendering interface, mainly for URDF-based robots.
///There is an implementation in
@ -20,7 +21,10 @@ struct UrdfRenderingInterface
///Given b3VisualShapeData, add render information (texture, rgbaColor etc) to the visualShape
///and visualShape to internal renderer.
///Returns a visualShapeUniqueId as a unique identifier to synchronize the world transform and to remove the visual shape.
virtual int addVisualShape(struct b3VisualShapeData* visualShape, struct CommonFileIOInterface* fileIO) = 0;
virtual int addVisualShape(struct b3VisualShapeData* visualShape, struct CommonFileIOInterface* fileIO, int orgGraphicsUniqueId,
int bodyUniqueId, int linkIndex) = 0;
virtual void updateShape(int shapeUniqueId, const btVector3* vertices, int numVertices) = 0;
///remove a visual shapes, based on the shape unique id (shapeUid)
virtual void removeVisualShape(int collisionObjectUid) = 0;
@ -37,6 +41,9 @@ struct UrdfRenderingInterface
///change the RGBA color for some visual shape.
virtual void changeRGBAColor(int bodyUniqueId, int linkIndex, int shapeIndex, const double rgbaColor[4]) = 0;
//change the instance flags, double-sided rendering
virtual void changeInstanceFlags(int bodyUniqueId, int linkIndex, int shapeIndex, int flags) = 0;
///select a given texture for some visual shape.
virtual void changeShapeTexture(int objectUniqueId, int linkIndex, int shapeIndex, int textureUniqueId) = 0;

View File

@ -24,10 +24,10 @@ files {
"../RenderingExamples/TimeSeriesCanvas.cpp",
"../RenderingExamples/TimeSeriesFontData.cpp",
"../MultiBody/InvertedPendulumPDControl.cpp",
"../ThirdPartyLibs/tinyxml/tinystr.cpp",
"../ThirdPartyLibs/tinyxml/tinyxml.cpp",
"../ThirdPartyLibs/tinyxml/tinyxmlerror.cpp",
"../ThirdPartyLibs/tinyxml/tinyxmlparser.cpp",
"../ThirdPartyLibs/tinyxml2/tinystr.cpp",
"../ThirdPartyLibs/tinyxml2/tinyxml.cpp",
"../ThirdPartyLibs/tinyxml2/tinyxmlerror.cpp",
"../ThirdPartyLibs/tinyxml2/tinyxmlparser.cpp",
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp",
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.h",
"../Importers/ImportColladaDemo/LoadMeshFromCollada.cpp",
@ -76,10 +76,10 @@ files {
"../RenderingExamples/TimeSeriesCanvas.cpp",
"../RenderingExamples/TimeSeriesFontData.cpp",
"../MultiBody/InvertedPendulumPDControl.cpp",
"../ThirdPartyLibs/tinyxml/tinystr.cpp",
"../ThirdPartyLibs/tinyxml/tinyxml.cpp",
"../ThirdPartyLibs/tinyxml/tinyxmlerror.cpp",
"../ThirdPartyLibs/tinyxml/tinyxmlparser.cpp",
"../ThirdPartyLibs/tinyxml2/tinystr.cpp",
"../ThirdPartyLibs/tinyxml2/tinyxml.cpp",
"../ThirdPartyLibs/tinyxml2/tinyxmlerror.cpp",
"../ThirdPartyLibs/tinyxml2/tinyxmlparser.cpp",
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp",
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.h",
"../Importers/ImportColladaDemo/LoadMeshFromCollada.cpp",
@ -142,10 +142,10 @@ files {
"../RenderingExamples/TimeSeriesCanvas.cpp",
"../RenderingExamples/TimeSeriesFontData.cpp",
"../MultiBody/InvertedPendulumPDControl.cpp",
"../ThirdPartyLibs/tinyxml/tinystr.cpp",
"../ThirdPartyLibs/tinyxml/tinyxml.cpp",
"../ThirdPartyLibs/tinyxml/tinyxmlerror.cpp",
"../ThirdPartyLibs/tinyxml/tinyxmlparser.cpp",
"../ThirdPartyLibs/tinyxml2/tinystr.cpp",
"../ThirdPartyLibs/tinyxml2/tinyxml.cpp",
"../ThirdPartyLibs/tinyxml2/tinyxmlerror.cpp",
"../ThirdPartyLibs/tinyxml2/tinyxmlparser.cpp",
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp",
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.h",
"../Importers/ImportColladaDemo/LoadMeshFromCollada.cpp",
@ -201,10 +201,10 @@ files {
"../RenderingExamples/TimeSeriesCanvas.cpp",
"../RenderingExamples/TimeSeriesFontData.cpp",
"../MultiBody/InvertedPendulumPDControl.cpp",
"../ThirdPartyLibs/tinyxml/tinystr.cpp",
"../ThirdPartyLibs/tinyxml/tinyxml.cpp",
"../ThirdPartyLibs/tinyxml/tinyxmlerror.cpp",
"../ThirdPartyLibs/tinyxml/tinyxmlparser.cpp",
"../ThirdPartyLibs/tinyxml2/tinystr.cpp",
"../ThirdPartyLibs/tinyxml2/tinyxml.cpp",
"../ThirdPartyLibs/tinyxml2/tinyxmlerror.cpp",
"../ThirdPartyLibs/tinyxml2/tinyxmlparser.cpp",
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp",
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.h",
"../Importers/ImportColladaDemo/LoadMeshFromCollada.cpp",

View File

@ -46,7 +46,7 @@ SamplelsMemoryReleaseFunc,
b3ThreadSupportInterface* createThreadSupport(int numThreads)
{
b3Win32ThreadSupport::Win32ThreadConstructionInfo threadConstructionInfo("testThreads", SampleThreadFunc, SamplelsMemoryFunc, numThreads);
b3Win32ThreadSupport::Win32ThreadConstructionInfo threadConstructionInfo("testThreads", SampleThreadFunc, SamplelsMemoryFunc, SamplelsMemoryReleaseFunc, numThreads);
b3Win32ThreadSupport* threadSupport = new b3Win32ThreadSupport(threadConstructionInfo);
return threadSupport;
}

View File

@ -1104,10 +1104,13 @@ void GLInstancingRenderer::activateTexture(int textureIndex)
}
}
void GLInstancingRenderer::updateShape(int shapeIndex, const float* vertices)
void GLInstancingRenderer::updateShape(int shapeIndex, const float* vertices, int numVertices)
{
b3GraphicsInstance* gfxObj = m_graphicsInstances[shapeIndex];
int numvertices = gfxObj->m_numVertices;
b3Assert(numvertices == numVertices);
if (numvertices != numVertices)
return;
glBindBuffer(GL_ARRAY_BUFFER, m_data->m_vbo);
int vertexStrideInBytes = 9 * sizeof(float);

View File

@ -53,7 +53,7 @@ public:
virtual void removeAllInstances();
virtual void removeGraphicsInstance(int instanceUid);
virtual void updateShape(int shapeIndex, const float* vertices);
virtual void updateShape(int shapeIndex, const float* vertices, int numVertices);
///vertices must be in the format x,y,z, nx,ny,nz, u,v
virtual int registerShape(const float* vertices, int numvertices, const int* indices, int numIndices, int primitiveType = B3_GL_TRIANGLES, int textureIndex = -1);

View File

@ -637,10 +637,13 @@ void SimpleOpenGL2Renderer::drawPoint(const double* position, const double color
{
}
void SimpleOpenGL2Renderer::updateShape(int shapeIndex, const float* vertices)
void SimpleOpenGL2Renderer::updateShape(int shapeIndex, const float* vertices, int numVertices)
{
SimpleGL2Shape* shape = m_data->m_shapes[shapeIndex];
int numvertices = shape->m_vertices.size();
b3Assert(numVertices = numvertices);
if (numVertices != numvertices)
return;
for (int i = 0; i < numvertices; i++)
{

View File

@ -81,7 +81,7 @@ public:
virtual void drawPoint(const double* position, const double color[4], double pointDrawSize);
virtual void updateShape(int shapeIndex, const float* vertices);
virtual void updateShape(int shapeIndex, const float* vertices, int numVertices);
virtual void clearZBuffer();

View File

@ -434,7 +434,7 @@ public:
args.m_useBendingSprings = true;
args.m_startPosition.setValue(0, 0, 0);
args.m_startOrientation.setValue(0, 0, 1, 1);
m_robotSim.loadDeformableBody("flat_napkin.obj", args);
//m_robotSim.loadDeformableBody("flat_napkin.obj", args);
b3JointInfo revoluteJoint1;
revoluteJoint1.m_parentFrame[0] = -0.055;

View File

@ -1429,6 +1429,18 @@ B3_SHARED_API void b3GetMeshDataSetCollisionShapeIndex(b3SharedMemoryCommandHand
}
}
B3_SHARED_API void b3GetMeshDataSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
b3Assert(command);
b3Assert(command->m_type == CMD_REQUEST_MESH_DATA);
if (command->m_type == CMD_REQUEST_MESH_DATA)
{
command->m_updateFlags = B3_MESH_DATA_FLAGS;
command->m_requestMeshDataArgs.m_flags = flags;
}
}
B3_SHARED_API void b3GetMeshData(b3PhysicsClientHandle physClient, struct b3MeshData* meshData)
{
PhysicsClient* cl = (PhysicsClient*)physClient;
@ -4933,6 +4945,7 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitUpdateVisualShape2(b3PhysicsClie
command->m_updateVisualShapeDataArguments.m_jointIndex = jointIndex;
command->m_updateVisualShapeDataArguments.m_shapeIndex = shapeIndex;
command->m_updateVisualShapeDataArguments.m_textureUniqueId = -2;
command->m_updateVisualShapeDataArguments.m_flags = 0;
command->m_updateFlags = 0;
return (b3SharedMemoryCommandHandle)command;
}
@ -4969,6 +4982,21 @@ B3_SHARED_API void b3UpdateVisualShapeRGBAColor(b3SharedMemoryCommandHandle comm
}
}
B3_SHARED_API void b3UpdateVisualShapeFlags(b3SharedMemoryCommandHandle commandHandle, int flags)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
b3Assert(command);
b3Assert(command->m_type == CMD_UPDATE_VISUAL_SHAPE);
if (command->m_type == CMD_UPDATE_VISUAL_SHAPE)
{
command->m_updateVisualShapeDataArguments.m_flags = flags;
command->m_updateFlags |= CMD_UPDATE_VISUAL_SHAPE_FLAGS;
}
}
B3_SHARED_API void b3UpdateVisualShapeSpecularColor(b3SharedMemoryCommandHandle commandHandle, const double specularColor[3])
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;

View File

@ -333,6 +333,8 @@ extern "C"
B3_SHARED_API b3SharedMemoryCommandHandle b3InitUpdateVisualShape2(b3PhysicsClientHandle physClient, int bodyUniqueId, int jointIndex, int shapeIndex);
B3_SHARED_API void b3UpdateVisualShapeTexture(b3SharedMemoryCommandHandle commandHandle, int textureUniqueId);
B3_SHARED_API void b3UpdateVisualShapeRGBAColor(b3SharedMemoryCommandHandle commandHandle, const double rgbaColor[/*4*/]);
B3_SHARED_API void b3UpdateVisualShapeFlags(b3SharedMemoryCommandHandle commandHandle, int flags);
B3_SHARED_API void b3UpdateVisualShapeSpecularColor(b3SharedMemoryCommandHandle commandHandle, const double specularColor[/*3*/]);
B3_SHARED_API b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient);
@ -516,7 +518,8 @@ extern "C"
B3_SHARED_API b3SharedMemoryCommandHandle b3GetMeshDataCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, int linkIndex);
B3_SHARED_API void b3GetMeshDataSetCollisionShapeIndex(b3SharedMemoryCommandHandle commandHandle, int shapeIndex);
B3_SHARED_API void b3GetMeshDataSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags);
B3_SHARED_API void b3GetMeshData(b3PhysicsClientHandle physClient, struct b3MeshData* meshData);

View File

@ -265,6 +265,8 @@ struct InternalBodyData
btRigidBody* m_rigidBody;
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
btSoftBody* m_softBody;
struct GLInstanceGraphicsShape* m_softBodyGfxShape;
#endif
int m_testData;
std::string m_bodyName;
@ -291,6 +293,7 @@ struct InternalBodyData
m_rigidBody = 0;
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
m_softBody = 0;
m_softBodyGfxShape = 0;
#endif
m_testData = 0;
m_bodyName = "";
@ -2575,7 +2578,16 @@ struct ProgrammaticUrdfInterface : public URDFImporterInterface
if (m_data->m_pluginManager.getRenderInterface())
{
CommonFileIOInterface* fileIO = m_data->m_pluginManager.getFileIOInterface();
int visualShapeUniqueid = m_data->m_pluginManager.getRenderInterface()->convertVisualShapes(linkIndex, pathPrefix, localInertiaFrame, &link, &model, colObj->getBroadphaseHandle()->getUid(), bodyUniqueId, fileIO);
int visualShapeUniqueid = m_data->m_pluginManager.getRenderInterface()->convertVisualShapes(
linkIndex,
pathPrefix,
localInertiaFrame,
&link,
&model,
colObj->getBroadphaseHandle()->getUid(),
bodyUniqueId,
fileIO);
colObj->setUserIndex3(visualShapeUniqueid);
}
}
@ -4089,6 +4101,43 @@ bool PhysicsServerCommandProcessor::processRequestCameraImageCommand(const struc
{
const btCollisionObject* colObj = m_data->m_dynamicsWorld->getCollisionObjectArray()[i];
m_data->m_pluginManager.getRenderInterface()->syncTransform(colObj->getUserIndex3(), colObj->getWorldTransform(), colObj->getCollisionShape()->getLocalScaling());
const btCollisionShape* collisionShape = colObj->getCollisionShape();
if (collisionShape->getShapeType() == SOFTBODY_SHAPE_PROXYTYPE)
{
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
const btSoftBody* psb = (const btSoftBody*)colObj;
if (psb->getUserIndex3() >= 0)
{
btAlignedObjectArray<btVector3> vertices;
if (psb->m_renderNodes.size() == 0)
{
vertices.resize(psb->m_faces.size() * 3);
for (int i = 0; i < psb->m_faces.size(); i++) // Foreach face
{
for (int k = 0; k < 3; k++) // Foreach vertex on a face
{
int currentIndex = i * 3 + k;
vertices[currentIndex] = psb->m_faces[i].m_n[k]->m_x;
}
}
}
else
{
vertices.resize(psb->m_renderNodes.size());
for (int i = 0; i < psb->m_renderNodes.size(); i++) // Foreach face
{
vertices[i] = psb->m_renderNodes[i].m_x;
}
}
m_data->m_pluginManager.getRenderInterface()->updateShape(psb->getUserIndex3(), &vertices[0], vertices.size());
}
#endif //SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
}
}
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES) != 0)
@ -5375,23 +5424,33 @@ bool PhysicsServerCommandProcessor::processRequestMeshDataCommand(const struct S
{
btSoftBody* psb = bodyHandle->m_softBody;
bool separateRenderMesh = (psb->m_renderNodes.size() != 0);
int flags = 0;
if (clientCmd.m_updateFlags & B3_MESH_DATA_FLAGS)
{
flags = clientCmd.m_requestMeshDataArgs.m_flags;
}
bool separateRenderMesh = false;
if ((flags & B3_MESH_DATA_SIMULATION_MESH) == 0)
{
separateRenderMesh = (psb->m_renderNodes.size() != 0);
}
int numVertices = separateRenderMesh ? psb->m_renderNodes.size() : psb->m_nodes.size();
int maxNumVertices = bufferSizeInBytes / totalBytesPerVertex - 1;
int numVerticesRemaining = numVertices - clientCmd.m_requestMeshDataArgs.m_startingVertex;
int verticesCopied = btMin(maxNumVertices, numVerticesRemaining);
for (int i = 0; i < verticesCopied; ++i)
{
if (separateRenderMesh)
{
const btSoftBody::Node& n = psb->m_renderNodes[i + clientCmd.m_requestMeshDataArgs.m_startingVertex];
verticesOut[i] = n.m_x;
const btSoftBody::RenderNode& n = psb->m_renderNodes[i + clientCmd.m_requestMeshDataArgs.m_startingVertex];
verticesOut[i].setValue(n.m_x.x(), n.m_x.y(), n.m_x.z());
}
else
{
const btSoftBody::Node& n = psb->m_nodes[i + clientCmd.m_requestMeshDataArgs.m_startingVertex];
verticesOut[i] = n.m_x;
verticesOut[i].setValue(n.m_x.x(), n.m_x.y(), n.m_x.z());
}
}
sizeInBytes = verticesCopied * sizeof(btVector3);
@ -8609,63 +8668,103 @@ bool PhysicsServerCommandProcessor::processDeformable(const UrdfDeformable& defo
}
#endif
}
b3ImportMeshData meshData;
if (psb != NULL)
{
#ifndef SKIP_DEFORMABLE_BODY
btDeformableMultiBodyDynamicsWorld* deformWorld = getDeformableWorld();
if (deformWorld)
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
// load render mesh
if ((out_found_sim_filename != out_found_filename) || ((out_sim_type == UrdfGeometry::FILE_OBJ)))
{
// load render mesh
if (out_found_sim_filename != out_found_filename)
if (1)
{
// load render mesh
float rgbaColor[4] = { 1,1,1,1 };
if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(
out_found_filename.c_str(), meshData, fileIO))
{
tinyobj::attrib_t attribute;
std::vector<tinyobj::shape_t> shapes;
std::string err = tinyobj::LoadObj(attribute, shapes, out_found_filename.c_str(), pathPrefix, m_data->m_pluginManager.getFileIOInterface());
for (int s = 0; s < (int)shapes.size(); s++)
for (int v = 0; v < meshData.m_gfxShape->m_numvertices; v++)
{
tinyobj::shape_t& shape = shapes[s];
int faceCount = shape.mesh.indices.size();
int vertexCount = attribute.vertices.size() / 3;
for (int v = 0; v < vertexCount; v++)
{
btSoftBody::Node n;
n.m_x = btVector3(attribute.vertices[3 * v], attribute.vertices[3 * v + 1], attribute.vertices[3 * v + 2]);
psb->m_renderNodes.push_back(n);
}
for (int f = 0; f < faceCount; f += 3)
{
if (f < 0 && f >= int(shape.mesh.indices.size()))
{
continue;
}
tinyobj::index_t v_0 = shape.mesh.indices[f];
tinyobj::index_t v_1 = shape.mesh.indices[f + 1];
tinyobj::index_t v_2 = shape.mesh.indices[f + 2];
btSoftBody::Face ff;
ff.m_n[0] = &psb->m_renderNodes[v_0.vertex_index];
ff.m_n[1] = &psb->m_renderNodes[v_1.vertex_index];
ff.m_n[2] = &psb->m_renderNodes[v_2.vertex_index];
psb->m_renderFaces.push_back(ff);
}
btSoftBody::RenderNode n;
n.m_x.setValue(
meshData.m_gfxShape->m_vertices->at(v).xyzw[0],
meshData.m_gfxShape->m_vertices->at(v).xyzw[1],
meshData.m_gfxShape->m_vertices->at(v).xyzw[2]);
n.m_uv1.setValue(meshData.m_gfxShape->m_vertices->at(v).uv[0],
meshData.m_gfxShape->m_vertices->at(v).uv[1],
0.);
n.m_normal.setValue(meshData.m_gfxShape->m_vertices->at(v).normal[0],
meshData.m_gfxShape->m_vertices->at(v).normal[1],
meshData.m_gfxShape->m_vertices->at(v).normal[2]);
psb->m_renderNodes.push_back(n);
}
for (int f = 0; f < meshData.m_gfxShape->m_numIndices; f += 3)
{
btSoftBody::RenderFace ff;
ff.m_n[0] = &psb->m_renderNodes[meshData.m_gfxShape->m_indices->at(f + 0)];
ff.m_n[1] = &psb->m_renderNodes[meshData.m_gfxShape->m_indices->at(f + 1)];
ff.m_n[2] = &psb->m_renderNodes[meshData.m_gfxShape->m_indices->at(f + 2)];
psb->m_renderFaces.push_back(ff);
}
}
if (out_sim_type == UrdfGeometry::FILE_VTK)
{
btSoftBodyHelpers::interpolateBarycentricWeights(psb);
}
else if (out_sim_type == UrdfGeometry::FILE_OBJ)
{
btSoftBodyHelpers::extrapolateBarycentricWeights(psb);
}
}
else
{
psb->m_renderNodes.resize(0);
tinyobj::attrib_t attribute;
std::vector<tinyobj::shape_t> shapes;
std::string err = tinyobj::LoadObj(attribute, shapes, out_found_filename.c_str(), pathPrefix, m_data->m_pluginManager.getFileIOInterface());
for (int s = 0; s < (int)shapes.size(); s++)
{
tinyobj::shape_t& shape = shapes[s];
int faceCount = shape.mesh.indices.size();
int vertexCount = attribute.vertices.size() / 3;
for (int v = 0; v < vertexCount; v++)
{
btSoftBody::RenderNode n;
n.m_x = btVector3(attribute.vertices[3 * v], attribute.vertices[3 * v + 1], attribute.vertices[3 * v + 2]);
psb->m_renderNodes.push_back(n);
}
for (int f = 0; f < faceCount; f += 3)
{
if (f < 0 && f >= int(shape.mesh.indices.size()))
{
continue;
}
tinyobj::index_t v_0 = shape.mesh.indices[f];
tinyobj::index_t v_1 = shape.mesh.indices[f + 1];
tinyobj::index_t v_2 = shape.mesh.indices[f + 2];
btSoftBody::RenderFace ff;
ff.m_n[0] = &psb->m_renderNodes[v_0.vertex_index];
ff.m_n[1] = &psb->m_renderNodes[v_1.vertex_index];
ff.m_n[2] = &psb->m_renderNodes[v_2.vertex_index];
psb->m_renderFaces.push_back(ff);
}
}
}
if (out_sim_type == UrdfGeometry::FILE_VTK)
{
btSoftBodyHelpers::interpolateBarycentricWeights(psb);
}
else if (out_sim_type == UrdfGeometry::FILE_OBJ)
{
btSoftBodyHelpers::extrapolateBarycentricWeights(psb);
}
}
else
{
psb->m_renderNodes.resize(0);
}
#endif
#ifndef SKIP_DEFORMABLE_BODY
btDeformableMultiBodyDynamicsWorld* deformWorld = getDeformableWorld();
if (deformWorld)
{
btVector3 gravity = m_data->m_dynamicsWorld->getGravity();
btDeformableLagrangianForce* gravityForce = new btDeformableGravityForce(gravity);
deformWorld->addForce(psb, gravityForce);
@ -8735,10 +8834,32 @@ bool PhysicsServerCommandProcessor::processDeformable(const UrdfDeformable& defo
softWorld->addSoftBody(psb);
}
}
m_data->m_guiHelper->createCollisionShapeGraphicsObject(psb->getCollisionShape());
if (meshData.m_gfxShape)
{
int texUid = m_data->m_guiHelper->registerTexture(meshData.m_textureImage1, meshData.m_textureWidth, meshData.m_textureHeight);
int shapeUid = m_data->m_guiHelper->registerGraphicsShape(&meshData.m_gfxShape->m_vertices->at(0).xyzw[0], meshData.m_gfxShape->m_numvertices, &meshData.m_gfxShape->m_indices->at(0), meshData.m_gfxShape->m_numIndices, B3_GL_TRIANGLES, texUid);
psb->getCollisionShape()->setUserIndex(shapeUid);
float position[4] = { 0,0,0,0 };
float orientation [4] = { 0,0,0,1 };
float color[4] = { 1,1,1,1 };
float scaling[4] = { 1,1,1,1 };
int instanceUid = m_data->m_guiHelper->registerGraphicsInstance(shapeUid, position, orientation, color, scaling);
psb->setUserIndex(instanceUid);
delete meshData.m_gfxShape;
}
else
{
m_data->m_guiHelper->createCollisionShapeGraphicsObject(psb->getCollisionShape());
}
*bodyUniqueId = m_data->m_bodyHandles.allocHandle();
InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(*bodyUniqueId);
bodyHandle->m_softBody = psb;
if (meshData.m_gfxShape)
bodyHandle->m_softBodyGfxShape = meshData.m_gfxShape;
psb->setUserIndex2(*bodyUniqueId);
b3VisualShapeData visualShape;
@ -8770,7 +8891,33 @@ bool PhysicsServerCommandProcessor::processDeformable(const UrdfDeformable& defo
visualShape.m_textureUniqueId = -1;
visualShape.m_openglTextureId = -1;
m_data->m_pluginManager.getRenderInterface()->addVisualShape(&visualShape, fileIO);
int softBodyGraphicsShapeUid = m_data->m_pluginManager.getRenderInterface()->addVisualShape(&visualShape, fileIO, psb->getBroadphaseHandle()->getUid(),
*bodyUniqueId,-1);
psb->setUserIndex3(softBodyGraphicsShapeUid);
btAlignedObjectArray<btVector3> vertices;
if (psb->m_renderNodes.size() == 0)
{
vertices.resize(psb->m_faces.size() * 3);
for (int i = 0; i < psb->m_faces.size(); i++) // Foreach face
{
for (int k = 0; k < 3; k++) // Foreach vertex on a face
{
int currentIndex = i * 3 + k;
vertices[currentIndex] = psb->m_faces[i].m_n[k]->m_x;
}
}
}
else
{
vertices.resize(psb->m_renderNodes.size());
for (int i = 0; i < psb->m_renderNodes.size(); i++) // Foreach face
{
vertices[i] = psb->m_renderNodes[i].m_x;
}
}
m_data->m_pluginManager.getRenderInterface()->updateShape(psb->getUserIndex3(), &vertices[0], vertices.size());
if (!deformable.m_name.empty())
{
@ -11384,7 +11531,7 @@ bool PhysicsServerCommandProcessor::processCreateUserConstraintCommand(const str
if (nodeIndex >= 0 && nodeIndex < sbodyHandle->m_softBody->m_nodes.size())
{
int bodyUniqueId = clientCmd.m_userConstraintArguments.m_childBodyIndex;
if (bodyUniqueId <= 0)
if (bodyUniqueId < 0)
{
//fixed anchor (mass = 0)
InteralUserConstraintData userConstraintData;
@ -13026,6 +13173,20 @@ bool PhysicsServerCommandProcessor::processUpdateVisualShapeCommand(const struct
clientCmd.m_updateVisualShapeDataArguments.m_shapeIndex, clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
}
}
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_FLAGS)
{
if (m_data->m_pluginManager.getRenderInterface())
{
m_data->m_pluginManager.getRenderInterface()->changeInstanceFlags(bodyUniqueId, linkIndex,
clientCmd.m_updateVisualShapeDataArguments.m_shapeIndex,
clientCmd.m_updateVisualShapeDataArguments.m_flags);
}
int graphicsIndex = bodyHandle->m_softBody->getUserIndex();
m_data->m_guiHelper->changeInstanceFlags(graphicsIndex,
clientCmd.m_updateVisualShapeDataArguments.m_flags);
}
}
#endif
}

View File

@ -132,6 +132,7 @@ enum MultiThreadedGUIHelperCommunicationEnums
eGUIHelperChangeGraphicsInstanceScaling,
eGUIUserDebugRemoveAllParameters,
eGUIHelperResetCamera,
eGUIHelperChangeGraphicsInstanceFlags,
};
#include <stdio.h>
@ -1045,6 +1046,21 @@ public:
workerThreadWait();
}
int m_graphicsInstanceFlagsInstanceUid;
int m_graphicsInstanceFlags;
virtual void changeInstanceFlags(int instanceUid, int flags)
{
m_graphicsInstanceFlagsInstanceUid = instanceUid;
m_graphicsInstanceFlags = flags;
m_cs->lock();
m_cs->setSharedParam(1, eGUIHelperChangeGraphicsInstanceFlags);
workerThreadWait();
}
int m_graphicsInstanceChangeScaling;
double m_baseScaling[3];
virtual void changeScaling(int instanceUid, const double scaling[3])
@ -2244,6 +2260,13 @@ void PhysicsServerExample::updateGraphics()
break;
}
case eGUIHelperChangeGraphicsInstanceFlags:
{
m_multiThreadedHelper->m_childGuiHelper->changeInstanceFlags(m_multiThreadedHelper->m_graphicsInstanceFlagsInstanceUid, m_multiThreadedHelper->m_graphicsInstanceFlags);
m_multiThreadedHelper->mainThreadRelease();
break;
}
case eGUIHelperChangeGraphicsInstanceScaling:
{
B3_PROFILE("eGUIHelperChangeGraphicsInstanceScaling");

View File

@ -367,8 +367,11 @@ enum EnumUpdateVisualShapeData
CMD_UPDATE_VISUAL_SHAPE_TEXTURE = 1,
CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR = 2,
CMD_UPDATE_VISUAL_SHAPE_SPECULAR_COLOR = 4,
CMD_UPDATE_VISUAL_SHAPE_FLAGS = 8,
};
struct UpdateVisualShapeDataArgs
{
int m_bodyUniqueId;
@ -377,6 +380,7 @@ struct UpdateVisualShapeDataArgs
int m_textureUniqueId;
double m_rgbaColor[4];
double m_specularColor[3];
int m_flags;
};
struct LoadTextureArgs
@ -1117,6 +1121,7 @@ struct b3RequestMeshDataArgs
int m_linkIndex;
int m_startingVertex;
int m_collisionShapeIndex;
int m_flags;
};
struct b3SendMeshDataArgs

View File

@ -454,9 +454,17 @@ struct b3MeshVertex
};
enum eMeshDataFlags
{
B3_MESH_DATA_SIMULATION_MESH=1,
B3_MESH_DATA_SIMULATION_INDICES,
B3_MESH_DATA_GRAPHICS_INDICES,
};
enum eMeshDataEnum
{
B3_MESH_DATA_COLLISIONSHAPEINDEX=1,
B3_MESH_DATA_FLAGS=2,
};
struct b3MeshData
@ -1069,6 +1077,10 @@ enum eFileIOTypes
eInMemoryFileIO,
};
enum eEnumUpdateVisualShapeFlags
{
eVISUAL_SHAPE_DOUBLE_SIDED = 4,//see B3_INSTANCE_DOUBLE_SIDED
};
//limits for vertices/indices in PyBullet::createCollisionShape
//Make sure the data fits in SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE

View File

@ -78,12 +78,16 @@ struct EGLRendererObjectArray
int m_linkIndex;
btTransform m_worldTransform;
btVector3 m_localScaling;
b3ImportMeshData m_meshData;
int graphicsIndex;
EGLRendererObjectArray()
{
m_worldTransform.setIdentity();
m_localScaling.setValue(1, 1, 1);
graphicsIndex = -1;
}
};
//#define START_WIDTH 2560
@ -173,7 +177,7 @@ struct EGLRendererVisualShapeConverterInternalData
float m_mouseXpos;
float m_mouseYpos;
bool m_mouseInitialized;
int m_graphicsUniqueIdGenerator;
EGLRendererVisualShapeConverterInternalData()
: m_upAxis(2),
@ -201,8 +205,7 @@ struct EGLRendererVisualShapeConverterInternalData
m_mouseMoveMultiplier(0.4f),
m_mouseXpos(0.f),
m_mouseYpos(0.f),
m_mouseInitialized(false),
m_graphicsUniqueIdGenerator(15)
m_mouseInitialized(false)
{
m_depthBuffer.resize(m_swWidth * m_swHeight);
m_shadowBuffer.resize(m_swWidth * m_swHeight);
@ -905,27 +908,156 @@ static void convertURDFToVisualShape2(const UrdfShape* visual, const char* urdfP
}
static btVector4 sColors[4] =
{
{
btVector4(60. / 256., 186. / 256., 84. / 256., 1),
btVector4(244. / 256., 194. / 256., 13. / 256., 1),
btVector4(219. / 256., 50. / 256., 54. / 256., 1),
btVector4(72. / 256., 133. / 256., 237. / 256., 1),
//btVector4(1,1,0,1),
};
int EGLRendererVisualShapeConverter::addVisualShape(struct b3VisualShapeData* visualShape, struct CommonFileIOInterface* fileIO, int orgGraphicsUniqueId,
int bodyUniqueId, int linkIndex)
{
int uniqueId = orgGraphicsUniqueId;
visualShape->m_openglTextureId = -1;
visualShape->m_tinyRendererTextureId = -1;
visualShape->m_textureUniqueId = -1;
b3ImportMeshData meshData;
float rgbaColor[4] = { 1,1,1,1 };
EGLRendererObjectArray** visualsPtr = m_data->m_swRenderInstances[uniqueId];
if (visualsPtr == 0)
{
m_data->m_swRenderInstances.insert(uniqueId, new EGLRendererObjectArray);
}
visualsPtr = m_data->m_swRenderInstances[uniqueId];
if (visualsPtr)
{
EGLRendererObjectArray* visuals = *visualsPtr;
if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(
visualShape->m_meshAssetFileName, meshData, fileIO))
{
if (m_data->m_flags & URDF_USE_MATERIAL_COLORS_FROM_MTL)
{
if (meshData.m_flags & B3_IMPORT_MESH_HAS_RGBA_COLOR)
{
visualShape->m_rgbaColor[0] = meshData.m_rgbaColor[0];
visualShape->m_rgbaColor[1] = meshData.m_rgbaColor[1];
visualShape->m_rgbaColor[2] = meshData.m_rgbaColor[2];
if (m_data->m_flags & URDF_USE_MATERIAL_TRANSPARANCY_FROM_MTL)
{
visualShape->m_rgbaColor[3] = meshData.m_rgbaColor[3];
}
else
{
visualShape->m_rgbaColor[3] = 1;
}
for (int i = 0; i < 4; i++)
{
rgbaColor[i] = meshData.m_rgbaColor[i];
}
}
}
MyTexture3 texture;
if (meshData.m_textureImage1)
{
texture.m_width = meshData.m_textureWidth;
texture.m_height = meshData.m_textureHeight;
texture.textureData1 = meshData.m_textureImage1;
texture.m_isCached = meshData.m_isCached;
visualShape->m_tinyRendererTextureId = m_data->m_textures.size();
m_data->m_textures.push_back(texture);
}
// meshData.m_gfxShape is allocated by a helper function used to create visualShape,
// but is not needed in this use case here
}
//////////////
if (meshData.m_gfxShape)
{
B3_PROFILE("m_instancingRenderer register");
// register mesh to m_instancingRenderer too.
int shapeIndex = m_data->m_instancingRenderer->registerShape(&meshData.m_gfxShape->m_vertices->at(0).xyzw[0],
meshData.m_gfxShape->m_numvertices, &meshData.m_gfxShape->m_indices->at(0), meshData.m_gfxShape->m_numIndices, B3_GL_TRIANGLES,
visualShape->m_tinyRendererTextureId);
double scaling[3] = { 1, 1, 1 };
int graphicsIndex = m_data->m_instancingRenderer->registerGraphicsInstance(
shapeIndex,
&visualShape->m_localVisualFrame[0],
&visualShape->m_localVisualFrame[3],
&visualShape->m_rgbaColor[0], scaling);
int segmentationMask = visualShape->m_objectUniqueId + ((visualShape->m_linkIndex + 1) << 24);
{
if (graphicsIndex >= 0)
{
//visuals->m_graphicsInstanceIds.push_back(graphicsIndex);
if (m_data->m_graphicsIndexToSegmentationMask.size() < (graphicsIndex + 1))
{
m_data->m_graphicsIndexToSegmentationMask.resize(graphicsIndex + 1);
}
m_data->m_graphicsIndexToSegmentationMask[graphicsIndex] = segmentationMask;
}
}
m_data->m_instancingRenderer->writeTransforms();
visuals->m_meshData = meshData;
visuals->m_objectUniqueId = bodyUniqueId;
visuals->m_linkIndex = linkIndex;
visuals->graphicsIndex = graphicsIndex;
m_data->m_visualShapes.push_back(*visualShape);// meshData.m_gfxShape);
}
}
return uniqueId;
}
void EGLRendererVisualShapeConverter::updateShape(int shapeUniqueId, const btVector3* vertices, int numVertices)
{
EGLRendererObjectArray** visualsPtr = m_data->m_swRenderInstances[shapeUniqueId];
if (visualsPtr)
{
EGLRendererObjectArray* visuals = *visualsPtr;
btAssert(visuals->graphicsIndex >= 0);
if (visuals->graphicsIndex >= 0)
{
btAssert(visuals->m_meshData.m_gfxShape->m_numvertices == numVertices);
if (visuals->m_meshData.m_gfxShape->m_numvertices == numVertices)
{
for (int i = 0; i < numVertices; i++)
{
visuals->m_meshData.m_gfxShape->m_vertices->at(i).xyzw[0] = vertices[i][0];
visuals->m_meshData.m_gfxShape->m_vertices->at(i).xyzw[1] = vertices[i][1];
visuals->m_meshData.m_gfxShape->m_vertices->at(i).xyzw[2] = vertices[i][2];
}
}
m_data->m_instancingRenderer->updateShape(visuals->graphicsIndex, &visuals->m_meshData.m_gfxShape->m_vertices->at(0).xyzw[0],
visuals->m_meshData.m_gfxShape->m_vertices->size());
}
}
}
// If you are getting segfaults in this function it may be ecause you are
// compliling the plugin with differently from pybullet, try complining the
// compliling the plugin with differently from pybullet, try compiling the
// plugin with distutils too.
int EGLRendererVisualShapeConverter::convertVisualShapes(
int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame,
const UrdfLink* linkPtr, const UrdfModel* model,
int orgGraphicsUniqueId, int bodyUniqueId, struct CommonFileIOInterface* fileIO)
{
if (orgGraphicsUniqueId< 0)
{
orgGraphicsUniqueId = m_data->m_graphicsUniqueIdGenerator++;
}
btAssert(orgGraphicsUniqueId >= 0);
btAssert(linkPtr); // TODO: remove if (not doing it now, because diff will be 50+ lines)
if (linkPtr)
{
@ -1196,6 +1328,19 @@ int EGLRendererVisualShapeConverter::getVisualShapesData(int bodyUniqueId, int s
return 0;
}
void EGLRendererVisualShapeConverter::changeInstanceFlags(int bodyUniqueId, int linkIndex, int shapeIndex, int flags)
{
for (int i = 0; i < m_data->m_swRenderInstances.size(); i++)
{
EGLRendererObjectArray** ptrptr = m_data->m_swRenderInstances.getAtIndex(i);
if (ptrptr && *ptrptr)
{
EGLRendererObjectArray* visuals = *ptrptr;
m_data->m_instancingRenderer->writeSingleInstanceFlagsToCPU(flags, visuals->graphicsIndex);
}
}
}
void EGLRendererVisualShapeConverter::changeRGBAColor(int bodyUniqueId, int linkIndex, int shapeIndex, const double rgbaColor[4])
{
//int start = -1;
@ -1220,7 +1365,7 @@ void EGLRendererVisualShapeConverter::changeRGBAColor(int bodyUniqueId, int link
EGLRendererObjectArray* visuals = *ptrptr;
if ((bodyUniqueId == visuals->m_objectUniqueId) && (linkIndex == visuals->m_linkIndex))
{
m_data->m_instancingRenderer->writeSingleInstanceColorToCPU(rgbaColor, visuals->graphicsIndex);
}
}
}
@ -1241,6 +1386,7 @@ void EGLRendererVisualShapeConverter::resetCamera(float camDist, float yaw, floa
m_data->m_camera.setCameraTargetPosition(camPosX, camPosY, camPosZ);
m_data->m_camera.setAspectRatio((float)m_data->m_swWidth / (float)m_data->m_swHeight);
m_data->m_camera.update();
}
void EGLRendererVisualShapeConverter::clearBuffers(TGAColor& clearColor)
@ -1579,10 +1725,11 @@ void EGLRendererVisualShapeConverter::resetAll()
EGLRendererObjectArray* ptr = *ptrptr;
if (ptr)
{
delete ptr->m_meshData.m_gfxShape;
}
delete ptr;
}
}
for (int i = 0; i < m_data->m_textures.size(); i++)

View File

@ -17,10 +17,15 @@ struct EGLRendererVisualShapeConverter : public UrdfRenderingInterface
virtual int getVisualShapesData(int bodyUniqueId, int shapeIndex, struct b3VisualShapeData* shapeData);
virtual int addVisualShape(b3VisualShapeData* visualShape, struct CommonFileIOInterface* fileIO) { return -1; }
virtual int addVisualShape(struct b3VisualShapeData* visualShape, struct CommonFileIOInterface* fileIO, int orgGraphicsUniqueId,
int bodyUniqueId, int linkIndex);
virtual void updateShape(int shapeUniqueId, const btVector3* vertices, int numVertices);
virtual void changeRGBAColor(int bodyUniqueId, int linkIndex, int shapeIndex, const double rgbaColor[4]);
virtual void changeInstanceFlags(int bodyUniqueId, int linkIndex, int shapeIndex, int flags);
virtual void changeShapeTexture(int objectUniqueId, int linkIndex, int shapeIndex, int textureUniqueId);
virtual void removeVisualShape(int shapeUid);

View File

@ -68,7 +68,7 @@ struct TinyRendererVisualShapeConverterInternalData
btAlignedObjectArray<unsigned char> m_checkeredTexels;
int m_uidGenerator;
int m_upAxis;
int m_swWidth;
int m_swHeight;
@ -94,8 +94,7 @@ struct TinyRendererVisualShapeConverterInternalData
SimpleCamera m_camera;
TinyRendererVisualShapeConverterInternalData()
: m_uidGenerator(1),
m_upAxis(2),
: m_upAxis(2),
m_swWidth(START_WIDTH),
m_swHeight(START_HEIGHT),
m_rgbColorBuffer(START_WIDTH, START_HEIGHT, TGAImage::RGB),
@ -711,11 +710,12 @@ static btVector4 sGoogleyColors[4] =
int TinyRendererVisualShapeConverter::convertVisualShapes(
int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame,
const UrdfLink* linkPtr, const UrdfModel* model, int unused,
const UrdfLink* linkPtr, const UrdfModel* model, int orgGraphicsUniqueId,
int bodyUniqueId, struct CommonFileIOInterface* fileIO)
{
int uniqueId = m_data->m_uidGenerator++;
int uniqueId = orgGraphicsUniqueId;
btAssert(orgGraphicsUniqueId >= 0);
btAssert(linkPtr); // TODO: remove if (not doing it now, because diff will be 50+ lines)
if (linkPtr)
{
@ -926,13 +926,17 @@ int TinyRendererVisualShapeConverter::convertVisualShapes(
}
int TinyRendererVisualShapeConverter::addVisualShape(
b3VisualShapeData* visualShape, struct CommonFileIOInterface* fileIO)
b3VisualShapeData* visualShape, struct CommonFileIOInterface* fileIO, int orgGraphicsUniqueId,
int bodyUniqueId, int linkIndex)
{
int uniqueId = m_data->m_uidGenerator++;
int uniqueId = orgGraphicsUniqueId;
visualShape->m_openglTextureId = -1;
visualShape->m_tinyRendererTextureId = -1;
visualShape->m_textureUniqueId = -1;
b3ImportMeshData meshData;
float rgbaColor[4] = { 1,1,1,1 };
if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(
visualShape->m_meshAssetFileName, meshData, fileIO))
{
@ -952,6 +956,10 @@ int TinyRendererVisualShapeConverter::addVisualShape(
{
visualShape->m_rgbaColor[3] = 1;
}
for (int i = 0; i < 4; i++)
{
rgbaColor[i] = meshData.m_rgbaColor[i];
}
}
}
@ -968,7 +976,7 @@ int TinyRendererVisualShapeConverter::addVisualShape(
}
// meshData.m_gfxShape is allocated by a helper function used to create visualShape,
// but is not needed in this use case here
delete meshData.m_gfxShape;
}
btAlignedObjectArray<b3VisualShapeData>* shapes =
@ -979,10 +987,87 @@ int TinyRendererVisualShapeConverter::addVisualShape(
btAlignedObjectArray<b3VisualShapeData>());
shapes = m_data->m_visualShapesMap[visualShape->m_objectUniqueId];
}
//////////////
if (meshData.m_gfxShape)
{
if (meshData.m_gfxShape->m_numvertices && meshData.m_gfxShape->m_numIndices)
{
TinyRenderObjectData* tinyObj = new TinyRenderObjectData(m_data->m_rgbColorBuffer, m_data->m_depthBuffer, &m_data->m_shadowBuffer, &m_data->m_segmentationMaskBuffer, -1, -1);
//those are primary soft bodies, possibly cloth, make them double-sided by default
tinyObj->m_doubleSided = true;
{
B3_PROFILE("registerMeshShape");
tinyObj->registerMeshShape(&meshData.m_gfxShape->m_vertices->at(0).xyzw[0],
meshData.m_gfxShape->m_numvertices,
&meshData.m_gfxShape->m_indices->at(0),
meshData.m_gfxShape->m_numIndices,
rgbaColor,
meshData.m_textureImage1, meshData.m_textureWidth, meshData.m_textureHeight);
}
TinyRendererObjectArray** visualsPtr = m_data->m_swRenderInstances[uniqueId];
if (visualsPtr == 0)
{
m_data->m_swRenderInstances.insert(uniqueId, new TinyRendererObjectArray);
}
visualsPtr = m_data->m_swRenderInstances[uniqueId];
if (visualsPtr && *visualsPtr)
{
TinyRendererObjectArray* visuals = *visualsPtr;
if (visuals)
{
visuals->m_linkIndex = linkIndex;
visuals->m_objectUniqueId = bodyUniqueId;
visuals->m_renderObjects.push_back(tinyObj);
}
}
}
delete meshData.m_gfxShape;
}
shapes->push_back(*visualShape);
return uniqueId;
}
void TinyRendererVisualShapeConverter::updateShape(int shapeUniqueId, const btVector3* vertices, int numVertices)
{
TinyRendererObjectArray** visualsPtr = m_data->m_swRenderInstances[shapeUniqueId];
if (visualsPtr != 0)
{
TinyRendererObjectArray* visuals = *visualsPtr;
if (visuals->m_renderObjects.size() == 1)
{
TinyRenderObjectData* renderObj = visuals->m_renderObjects[0];
if (renderObj->m_model->nverts() == numVertices)
{
TinyRender::Vec3f* verts = renderObj->m_model->readWriteVertices();
//just do a sync
for (int i = 0; i < numVertices; i++)
{
verts[i].x = vertices[i][0];
verts[i].y = vertices[i][1];
verts[i].z = vertices[i][2];
}
}
}
}
}
int TinyRendererVisualShapeConverter::getNumVisualShapes(int bodyUniqueId)
{
btAlignedObjectArray<b3VisualShapeData>* shapes = m_data->m_visualShapesMap[bodyUniqueId];
@ -1008,6 +1093,37 @@ int TinyRendererVisualShapeConverter::getVisualShapesData(int bodyUniqueId, int
return 1;
}
void TinyRendererVisualShapeConverter::changeInstanceFlags(int bodyUniqueId, int linkIndex, int shapeIndex, int flags)
{
bool doubleSided = (flags & 4) != 0;
btAlignedObjectArray<b3VisualShapeData>* shapes = m_data->m_visualShapesMap[bodyUniqueId];
if (!shapes)
{
return;
}
int start = -1;
for (int i = 0; i < m_data->m_swRenderInstances.size(); i++)
{
TinyRendererObjectArray** ptrptr = m_data->m_swRenderInstances.getAtIndex(i);
if (ptrptr && *ptrptr)
{
TinyRendererObjectArray* visuals = *ptrptr;
if ((bodyUniqueId == visuals->m_objectUniqueId) && (linkIndex == visuals->m_linkIndex))
{
for (int q = 0; q < visuals->m_renderObjects.size(); q++)
{
if (shapeIndex < 0 || q == shapeIndex)
{
visuals->m_renderObjects[q]->m_doubleSided = doubleSided;
}
}
}
}
}
}
void TinyRendererVisualShapeConverter::changeRGBAColor(int bodyUniqueId, int linkIndex, int shapeIndex, const double rgbaColor[4])
{
btAlignedObjectArray<b3VisualShapeData>* shapes = m_data->m_visualShapesMap[bodyUniqueId];
@ -1376,6 +1492,8 @@ void TinyRendererVisualShapeConverter::removeVisualShape(int collisionObjectUniq
void TinyRendererVisualShapeConverter::resetAll()
{
for (int i = 0; i < m_data->m_swRenderInstances.size(); i++)
{
TinyRendererObjectArray** ptrptr = m_data->m_swRenderInstances.getAtIndex(i);

View File

@ -11,9 +11,12 @@ struct TinyRendererVisualShapeConverter : public UrdfRenderingInterface
virtual ~TinyRendererVisualShapeConverter();
virtual int convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfLink* linkPtr, const UrdfModel* model, int unused, int bodyUniqueId, struct CommonFileIOInterface* fileIO);
virtual int convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfLink* linkPtr, const UrdfModel* model, int orgGraphicsUniqueId, int bodyUniqueId, struct CommonFileIOInterface* fileIO);
virtual int addVisualShape(struct b3VisualShapeData* visualShape, struct CommonFileIOInterface* fileIO);
virtual int addVisualShape(struct b3VisualShapeData* visualShape, struct CommonFileIOInterface* fileIO, int orgGraphicsUniqueId,
int bodyUniqueId, int linkIndex);
virtual void updateShape(int shapeUniqueId, const btVector3* vertices, int numVertices);
virtual int getNumVisualShapes(int bodyUniqueId);
@ -21,6 +24,8 @@ struct TinyRendererVisualShapeConverter : public UrdfRenderingInterface
virtual void changeRGBAColor(int bodyUniqueId, int linkIndex, int shapeIndex, const double rgbaColor[4]);
virtual void changeInstanceFlags(int bodyUniqueId, int linkIndex, int shapeIndex, int flags);
virtual void changeShapeTexture(int objectUniqueId, int linkIndex, int shapeIndex, int textureUniqueId);
virtual void removeVisualShape(int shapeUid);

View File

@ -105,7 +105,7 @@ std::string GetUserDocumentsPath();
#endif
//-----------------------------------------------------------------------------
#if defined(WIN32)
#if defined(_WIN32)
#define DYNAMIC_LIB_EXT ".dll"
#ifdef _WIN64
#define PLATSUBDIR "win64"

View File

@ -200,7 +200,8 @@ TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer, b3AlignedOb
m_segmentationMaskBufferPtr(0),
m_userData(0),
m_userIndex(-1),
m_objectIndex(-1)
m_objectIndex(-1),
m_doubleSided(false)
{
Vec3f eye(1, 1, 3);
Vec3f center(0, 0, 0);
@ -223,7 +224,8 @@ TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer, b3AlignedOb
m_userData(0),
m_userIndex(-1),
m_objectIndex(objectIndex),
m_linkIndex(linkIndex)
m_linkIndex(linkIndex),
m_doubleSided(false)
{
Vec3f eye(1, 1, 3);
Vec3f center(0, 0, 0);
@ -241,10 +243,12 @@ TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer, b3AlignedOb
: m_model(0),
m_rgbColorBuffer(rgbColorBuffer),
m_depthBuffer(depthBuffer),
m_shadowBuffer(0),
m_segmentationMaskBufferPtr(0),
m_userData(0),
m_userIndex(-1),
m_objectIndex(-1)
m_objectIndex(-1),
m_doubleSided(false)
{
Vec3f eye(1, 1, 3);
Vec3f center(0, 0, 0);
@ -262,10 +266,12 @@ TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer, b3AlignedOb
: m_model(0),
m_rgbColorBuffer(rgbColorBuffer),
m_depthBuffer(depthBuffer),
m_shadowBuffer(0),
m_segmentationMaskBufferPtr(segmentationMaskBuffer),
m_userData(0),
m_userIndex(-1),
m_objectIndex(objectIndex)
m_objectIndex(objectIndex),
m_doubleSided(false)
{
Vec3f eye(1, 1, 3);
Vec3f center(0, 0, 0);
@ -558,13 +564,16 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData)
shader.vertex(i, j);
}
// backface culling
btVector3 v0(shader.world_tri.col(0)[0], shader.world_tri.col(0)[1], shader.world_tri.col(0)[2]);
btVector3 v1(shader.world_tri.col(1)[0], shader.world_tri.col(1)[1], shader.world_tri.col(1)[2]);
btVector3 v2(shader.world_tri.col(2)[0], shader.world_tri.col(2)[1], shader.world_tri.col(2)[2]);
btVector3 N = (v1 - v0).cross(v2 - v0);
if ((v0 - P).dot(N) >= 0)
continue;
if (!renderData.m_doubleSided)
{
// backface culling
btVector3 v0(shader.world_tri.col(0)[0], shader.world_tri.col(0)[1], shader.world_tri.col(0)[2]);
btVector3 v1(shader.world_tri.col(1)[0], shader.world_tri.col(1)[1], shader.world_tri.col(1)[2]);
btVector3 v2(shader.world_tri.col(2)[0], shader.world_tri.col(2)[1], shader.world_tri.col(2)[2]);
btVector3 N = (v1 - v0).cross(v2 - v0);
if ((v0 - P).dot(N) >= 0)
continue;
}
mat<4, 3, float> stackTris[3];

View File

@ -53,6 +53,7 @@ struct TinyRenderObjectData
int m_userIndex;
int m_objectIndex;
int m_linkIndex;
bool m_doubleSided;
};
class TinyRenderer

View File

@ -2,7 +2,7 @@
#include "Bullet3Common/b3Quaternion.h"
#include "Bullet3Common/b3CommandLineArgs.h"
#include "Bullet3Common/b3Transform.h"
#include "Utils/b3BulletDefaultFileIO.h"
#include "assert.h"
#include <stdio.h>
@ -56,6 +56,7 @@ void MyKeyboardCallback(int keycode, int state)
sOldKeyboardCB(keycode, state);
}
#include "TinyRenderer.h"
float color2[4] = { 1,0,0,1 };
int main(int argc, char* argv[])
{
@ -85,8 +86,10 @@ int main(int argc, char* argv[])
TinyRenderObjectData renderData(rgbColorBuffer, depthBuffer); //, "african_head/african_head.obj");//floor.obj");
//renderData.loadModel("african_head/african_head.obj");
renderData.loadModel("floor.obj");
b3BulletDefaultFileIO fileIO;
//renderData.loadModel("african_head/african_head.obj", &fileIO);
renderData.loadModel("floor.obj",&fileIO);
//renderData.createCube(1,1,1);
@ -105,10 +108,10 @@ int main(int argc, char* argv[])
b3Vector3 pos = b3MakeVector3(0, 0, 0);
b3Quaternion orn(0, 0, 0, 1);
b3Vector3 color = b3MakeVector3(1, 0, 0);
b3Vector3 scaling = b3MakeVector3(1, 1, 1);
app->m_renderer->registerGraphicsInstance(cubeIndex, pos, orn, color, scaling);
app->m_renderer->writeTransforms();
//app->m_renderer->registerGraphicsInstance(cubeIndex, pos, orn, color, scaling);
//app->m_renderer->writeTransforms();
do
{
@ -153,7 +156,7 @@ int main(int argc, char* argv[])
tr.setIdentity();
static float posUp = 0.f;
// posUp += 0.001;
b3Vector3 org = b3MakeVector3(0, posUp, 0);
b3Vector3 org = b3MakeVector3(0, 0, posUp);
tr.setOrigin(org);
tr.getOpenGLMatrix(modelMat);
@ -167,6 +170,7 @@ int main(int argc, char* argv[])
}
//render the object
renderData.m_model->setColorRGBA(color2);
TinyRenderer::renderObject(renderData);
#if 1
@ -214,8 +218,8 @@ int main(int argc, char* argv[])
app->drawGrid();
char bla[1024];
sprintf(bla, "Simple test frame %d", frameCount);
app->drawText(bla, 10, 10);
float colorRGBA[4] = { 1,1,1,1 };
app->drawText(bla, 10, 10,1, colorRGBA);
app->swapBuffer();
} while (!app->m_window->requestedExit());

View File

@ -45,10 +45,17 @@ public:
~Model();
int nverts();
int nfaces();
Vec3f normal(int iface, int nthvert);
Vec3f normal(Vec2f uv);
Vec3f vert(int i);
Vec3f vert(int iface, int nthvert);
Vec3f* readWriteVertices()
{
if (verts_.size() == 0)
return 0;
return &verts_[0];
}
Vec2f uv(int iface, int nthvert);
TGAColor diffuse(Vec2f uv);
float specular(Vec2f uv);

View File

@ -4,35 +4,6 @@ import math
import pybullet_data
def getRayFromTo(mouseX, mouseY):
width, height, viewMat, projMat, cameraUp, camForward, horizon, vertical, _, _, dist, camTarget = p.getDebugVisualizerCamera(
)
camPos = [
camTarget[0] - dist * camForward[0], camTarget[1] - dist * camForward[1],
camTarget[2] - dist * camForward[2]
]
farPlane = 10000
rayForward = [(camTarget[0] - camPos[0]), (camTarget[1] - camPos[1]), (camTarget[2] - camPos[2])]
invLen = farPlane * 1. / (math.sqrt(rayForward[0] * rayForward[0] + rayForward[1] *
rayForward[1] + rayForward[2] * rayForward[2]))
rayForward = [invLen * rayForward[0], invLen * rayForward[1], invLen * rayForward[2]]
rayFrom = camPos
oneOverWidth = float(1) / float(width)
oneOverHeight = float(1) / float(height)
dHor = [horizon[0] * oneOverWidth, horizon[1] * oneOverWidth, horizon[2] * oneOverWidth]
dVer = [vertical[0] * oneOverHeight, vertical[1] * oneOverHeight, vertical[2] * oneOverHeight]
rayToCenter = [
rayFrom[0] + rayForward[0], rayFrom[1] + rayForward[1], rayFrom[2] + rayForward[2]
]
rayTo = [
rayToCenter[0] - 0.5 * horizon[0] + 0.5 * vertical[0] + float(mouseX) * dHor[0] -
float(mouseY) * dVer[0], rayToCenter[1] - 0.5 * horizon[1] + 0.5 * vertical[1] +
float(mouseX) * dHor[1] - float(mouseY) * dVer[1], rayToCenter[2] - 0.5 * horizon[2] +
0.5 * vertical[2] + float(mouseX) * dHor[2] - float(mouseY) * dVer[2]
]
return rayFrom, rayTo
cid = p.connect(p.SHARED_MEMORY)
if (cid < 0):
@ -64,8 +35,8 @@ collisionShapeId = p.createCollisionShape(shapeType=p.GEOM_MESH,
collisionFramePosition=shift,
meshScale=meshScale)
rangex = 5
rangey = 5
rangex = 1
rangey = 1
for i in range(rangex):
for j in range(rangey):
p.createMultiBody(baseMass=1,
@ -84,19 +55,4 @@ colors = [[1, 0, 0, 1], [0, 1, 0, 1], [0, 0, 1, 1], [1, 1, 1, 1]]
currentColor = 0
while (1):
mouseEvents = p.getMouseEvents()
for e in mouseEvents:
if ((e[0] == 2) and (e[3] == 0) and (e[4] & p.KEY_WAS_TRIGGERED)):
mouseX = e[1]
mouseY = e[2]
rayFrom, rayTo = getRayFromTo(mouseX, mouseY)
rayInfo = p.rayTest(rayFrom, rayTo)
#p.addUserDebugLine(rayFrom,rayTo,[1,0,0],3)
for l in range(len(rayInfo)):
hit = rayInfo[l]
objectUid = hit[0]
if (objectUid >= 1):
p.changeVisualShape(objectUid, -1, rgbaColor=colors[currentColor])
currentColor += 1
if (currentColor >= len(colors)):
currentColor = 0
time.sleep(1./240.)

View File

@ -11,22 +11,45 @@ gravZ=-10
p.setGravity(0, 0, gravZ)
planeOrn = [0,0,0,1]#p.getQuaternionFromEuler([0.3,0,0])
planeId = p.loadURDF("plane.urdf", [0,0,-2],planeOrn)
#planeId = p.loadURDF("plane.urdf", [0,0,-2],planeOrn)
boxId = p.loadURDF("cube.urdf", [0,1,2],useMaximalCoordinates = True)
clothId = p.loadSoftBody("cloth_z_up.obj", basePosition = [0,0,2], scale = 0.5, mass = 1., useNeoHookean = 0, useBendingSprings=1,useMassSpring=1, springElasticStiffness=40, springDampingStiffness=.1, springDampingAllDirections = 1, useSelfCollision = 0, frictionCoeff = .5, useFaceContact=1)
p.createSoftBodyAnchor(clothId ,0,-1,-1)
p.createSoftBodyAnchor(clothId ,1,-1,-1)
p.createSoftBodyAnchor(clothId ,3,boxId,-1, [0.5,-0.5,0])
p.createSoftBodyAnchor(clothId ,2,boxId,-1, [-0.5,-0.5,0])
p.setPhysicsEngineParameter(sparseSdfVoxelSize=0.25)
p.setRealTimeSimulation(1)
p.changeVisualShape(clothId, -1, flags=p.VISUAL_SHAPE_DOUBLE_SIDED)
p.createSoftBodyAnchor(clothId ,24,-1,-1)
p.createSoftBodyAnchor(clothId ,20,-1,-1)
p.createSoftBodyAnchor(clothId ,15,boxId,-1, [0.5,-0.5,0])
p.createSoftBodyAnchor(clothId ,19,boxId,-1, [-0.5,-0.5,0])
p.setPhysicsEngineParameter(sparseSdfVoxelSize=0.25)
debug = True
if debug:
data = p.getMeshData(clothId, -1, flags=p.MESH_DATA_SIMULATION_MESH)
print("--------------")
print("data=",data)
print(data[0])
print(data[1])
text_uid = []
for i in range(data[0]):
pos = data[1][i]
uid = p.addUserDebugText(str(i), pos, textColorRGB=[1,1,1])
text_uid.append(uid)
while p.isConnected():
p.setGravity(0,0,gravZ)
sleep(1./240.)
p.getCameraImage(320,200)
if debug:
data = p.getMeshData(clothId, -1, flags=p.MESH_DATA_SIMULATION_MESH)
for i in range(data[0]):
pos = data[1][i]
uid = p.addUserDebugText(str(i), pos, textColorRGB=[1,1,1], replaceItemUniqueId=text_uid[i])
p.setGravity(0,0,gravZ)
p.stepSimulation()
#p.configureDebugVisualizer(p.COV_ENABLE_SINGLE_STEP_RENDERING,1)
#sleep(1./240.)

View File

@ -14,17 +14,24 @@ planeId = p.loadURDF("plane.urdf", [0,0,-2],planeOrn)
boxId = p.loadURDF("cube.urdf", [0,3,2],useMaximalCoordinates = True)
ballId = p.loadSoftBody("ball.vtk", basePosition = [0,0,-1], scale = 0.5, mass = 4, useNeoHookean = 1, NeoHookeanMu = 400, NeoHookeanLambda = 600, NeoHookeanDamping = 0.001, useSelfCollision = 1, frictionCoeff = .5, collisionMargin = 0.001)
ballId = p.loadSoftBody("ball.obj", simFileName = "ball.vtk", basePosition = [0,0,-1], scale = 0.5, mass = 4, useNeoHookean = 1, NeoHookeanMu = 400, NeoHookeanLambda = 600, NeoHookeanDamping = 0.001, useSelfCollision = 1, frictionCoeff = .5, collisionMargin = 0.001)
p.setTimeStep(0.001)
p.setPhysicsEngineParameter(sparseSdfVoxelSize=0.25)
p.setRealTimeSimulation(1)
#logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "perf.json")
while p.isConnected():
p.stepSimulation()
#there can be some artifacts in the visualizer window,
#due to reading of deformable vertices in the renderer,
#while the simulators updates the same vertices
#it can be avoided using
#p.configureDebugVisualizer(p.COV_ENABLE_SINGLE_STEP_RENDERING,1)
#but then things go slower
p.setGravity(0,0,-10)
sleep(1./240.)
#sleep(1./240.)
#p.resetSimulation()
#p.stopStateLogging(logId)

View File

@ -14,9 +14,12 @@ planeId = p.loadURDF("plane.urdf", [0,0,-2])
boxId = p.loadURDF("cube.urdf", [0,3,2],useMaximalCoordinates = True)
bunnyId = p.loadSoftBody("torus.vtk", mass = 3, useNeoHookean = 1, NeoHookeanMu = 180, NeoHookeanLambda = 600, NeoHookeanDamping = 0.01, collisionMargin = 0.006, useSelfCollision = 1, frictionCoeff = 0.5, repulsionStiffness = 800)
bunnyId = p.loadSoftBody("torus/torus_textured.obj", simFileName="torus.vtk", mass = 3, useNeoHookean = 1, NeoHookeanMu = 180, NeoHookeanLambda = 600, NeoHookeanDamping = 0.01, collisionMargin = 0.006, useSelfCollision = 1, frictionCoeff = 0.5, repulsionStiffness = 800)
bunny2 = p.loadURDF("torus_deform.urdf", [0,1,0], flags=p.URDF_USE_SELF_COLLISION)
#ballId = p.loadSoftBody("ball.obj", simFileName = "ball.vtk", basePosition = [0,1,-1], scale = 0.5, mass = 4, useNeoHookean = 1, NeoHookeanMu = 400, NeoHookeanLambda = 600, NeoHookeanDamping = 0.001, useSelfCollision = 1, frictionCoeff = .5, collisionMargin = 0.001)
bunny2 = p.loadURDF("torus_deform.urdf", [0,1,0.5], flags=p.URDF_USE_SELF_COLLISION)
p.setPhysicsEngineParameter(sparseSdfVoxelSize=0.25)
p.setRealTimeSimulation(1)

View File

@ -1,3 +1,4 @@
#using the eglRendererPlugin (hardware OpenGL acceleration)
#using EGL on Linux and default OpenGL window on Win32.
@ -26,9 +27,10 @@ pybullet.setAdditionalSearchPath(pybullet_data.getDataPath())
egl = pkgutil.get_loader('eglRenderer')
if (egl):
pybullet.loadPlugin(egl.get_filename(), "_eglRendererPlugin")
pluginId = pybullet.loadPlugin(egl.get_filename(), "_eglRendererPlugin")
else:
pybullet.loadPlugin("eglRendererPlugin")
pluginId = pybullet.loadPlugin("eglRendererPlugin")
print("pluginId=",pluginId)
pybullet.loadURDF("plane.urdf", [0, 0, -1])
pybullet.loadURDF("r2d2.urdf")
@ -67,14 +69,14 @@ while (1):
lightDirection=[1, 1, 1],
renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
stop = time.time()
print("renderImage %f" % (stop - start))
#print("renderImage %f" % (stop - start))
w = img_arr[0] #width of the image, in pixels
h = img_arr[1] #height of the image, in pixels
rgb = img_arr[2] #color data RGB
dep = img_arr[3] #depth data
print('width = %d height = %d' % (w, h))
#print('width = %d height = %d' % (w, h))
#note that sending the data to matplotlib is really slow

View File

@ -2059,7 +2059,7 @@ static PyObject* pybullet_loadSoftBody(PyObject* self, PyObject* args, PyObject*
int physicsClientId = 0;
int flags = 0;
static char* kwlist[] = {"fileName", "basePosition", "baseOrientation", "scale", "mass", "collisionMargin", "useMassSpring", "useBendingSprings", "useNeoHookean", "springElasticStiffness", "springDampingStiffness", "springDampingAllDirections", "springBendingStiffness", "NeoHookeanMu", "NeoHookeanLambda", "NeoHookeanDamping", "frictionCoeff", "useFaceContact", "useSelfCollision", "repulsionStiffness", "physicsClientId", NULL};
static char* kwlist[] = {"fileName", "basePosition", "baseOrientation", "scale", "mass", "collisionMargin", "useMassSpring", "useBendingSprings", "useNeoHookean", "springElasticStiffness", "springDampingStiffness", "springDampingAllDirections", "springBendingStiffness", "NeoHookeanMu", "NeoHookeanLambda", "NeoHookeanDamping", "frictionCoeff", "useFaceContact", "useSelfCollision", "repulsionStiffness", "simFileName", "physicsClientId", NULL};
int bodyUniqueId = -1;
const char* fileName = "";
@ -2080,6 +2080,8 @@ static PyObject* pybullet_loadSoftBody(PyObject* self, PyObject* args, PyObject*
int useFaceContact = 0;
int useSelfCollision = 0;
double repulsionStiffness = 0.5;
const char* simFileName = "";
b3PhysicsClientHandle sm = 0;
@ -2090,7 +2092,29 @@ static PyObject* pybullet_loadSoftBody(PyObject* self, PyObject* args, PyObject*
PyObject* basePosObj = 0;
PyObject* baseOrnObj = 0;
if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|OOdddiiiddidddddiidi", kwlist, &fileName, &basePosObj, &baseOrnObj, &scale, &mass, &collisionMargin, &useMassSpring, &useBendingSprings, &useNeoHookean, &springElasticStiffness, &springDampingStiffness, &springDampingAllDirections, &springBendingStiffness, &NeoHookeanMu, &NeoHookeanLambda, &NeoHookeanDamping, &frictionCoeff, &useFaceContact, &useSelfCollision, &repulsionStiffness, &physicsClientId))
if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|OOdddiiiddidddddiidsi", kwlist,
&fileName,
&basePosObj,
&baseOrnObj,
&scale,
&mass,
&collisionMargin,
&useMassSpring,
&useBendingSprings,
&useNeoHookean,
&springElasticStiffness,
&springDampingStiffness,
&springDampingAllDirections,
&springBendingStiffness,
&NeoHookeanMu,
&NeoHookeanLambda,
&NeoHookeanDamping,
&frictionCoeff,
&useFaceContact,
&useSelfCollision,
&repulsionStiffness,
&simFileName,
&physicsClientId))
{
return NULL;
}
@ -2130,7 +2154,10 @@ static PyObject* pybullet_loadSoftBody(PyObject* self, PyObject* args, PyObject*
b3LoadSoftBodySetStartPosition(command, startPos[0], startPos[1], startPos[2]);
b3LoadSoftBodySetStartOrientation(command, startOrn[0], startOrn[1], startOrn[2], startOrn[3]);
if (strlen(simFileName))
{
b3LoadSoftBodyUpdateSimMesh(command, simFileName);
}
if (scale > 0)
{
b3LoadSoftBodySetScale(command, scale);
@ -7596,10 +7623,10 @@ static PyObject* pybullet_changeVisualShape(PyObject* self, PyObject* args, PyOb
int physicsClientId = 0;
PyObject* rgbaColorObj = 0;
PyObject* specularColorObj = 0;
int flags = -1;
b3PhysicsClientHandle sm = 0;
static char* kwlist[] = {"objectUniqueId", "linkIndex", "shapeIndex", "textureUniqueId", "rgbaColor", "specularColor", "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|iiOOi", kwlist, &objectUniqueId, &jointIndex, &shapeIndex, &textureUniqueId, &rgbaColorObj, &specularColorObj, &physicsClientId))
static char* kwlist[] = {"objectUniqueId", "linkIndex", "shapeIndex", "textureUniqueId", "rgbaColor", "specularColor", "flags", "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|iiOOii", kwlist, &objectUniqueId, &jointIndex, &shapeIndex, &textureUniqueId, &rgbaColorObj, &specularColorObj, &flags , &physicsClientId))
{
return NULL;
}
@ -7631,6 +7658,10 @@ static PyObject* pybullet_changeVisualShape(PyObject* self, PyObject* args, PyOb
pybullet_internalSetVector4d(rgbaColorObj, rgbaColor);
b3UpdateVisualShapeRGBAColor(commandHandle, rgbaColor);
}
if (flags >= 0)
{
b3UpdateVisualShapeFlags(commandHandle, flags);
}
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
statusType = b3GetStatusType(statusHandle);
@ -8835,10 +8866,11 @@ static PyObject* pybullet_getMeshData(PyObject* self, PyObject* args, PyObject*
b3SharedMemoryStatusHandle statusHandle;
struct b3MeshData meshData;
int statusType;
int flags = -1;
int physicsClientId = 0;
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "collisionShapeIndex", "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|iii", kwlist, &bodyUniqueId, &linkIndex,&collisionShapeIndex, &physicsClientId))
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "collisionShapeIndex", "flags", "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|iiii", kwlist, &bodyUniqueId, &linkIndex,&collisionShapeIndex, &flags , &physicsClientId))
{
return NULL;
}
@ -8853,6 +8885,11 @@ static PyObject* pybullet_getMeshData(PyObject* self, PyObject* args, PyObject*
{
b3GetMeshDataSetCollisionShapeIndex(command, collisionShapeIndex);
}
if (flags >= 0)
{
b3GetMeshDataSetFlags(command, flags);
}
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
statusType = b3GetStatusType(statusHandle);
if (statusType == CMD_REQUEST_MESH_DATA_COMPLETED)
@ -12938,6 +12975,7 @@ initpybullet(void)
PyModule_AddIntConstant(m, "URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS", URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS);
PyModule_AddIntConstant(m, "VISUAL_SHAPE_DATA_TEXTURE_UNIQUE_IDS", eVISUAL_SHAPE_DATA_TEXTURE_UNIQUE_IDS);
PyModule_AddIntConstant(m, "VISUAL_SHAPE_DOUBLE_SIDED", eVISUAL_SHAPE_DOUBLE_SIDED);
PyModule_AddIntConstant(m, "MAX_RAY_INTERSECTION_BATCH_SIZE", MAX_RAY_INTERSECTION_BATCH_SIZE_STREAMING);
@ -12989,6 +13027,8 @@ initpybullet(void)
PyModule_AddIntConstant(m, "STATE_LOG_JOINT_USER_TORQUES", STATE_LOG_JOINT_USER_TORQUES);
PyModule_AddIntConstant(m, "STATE_LOG_JOINT_TORQUES", STATE_LOG_JOINT_USER_TORQUES + STATE_LOG_JOINT_MOTOR_TORQUES);
PyModule_AddIntConstant(m, "MESH_DATA_SIMULATION_MESH", B3_MESH_DATA_SIMULATION_MESH);
PyModule_AddIntConstant(m, "AddFileIOAction", eAddFileIOAction);
PyModule_AddIntConstant(m, "RemoveFileIOAction", eRemoveFileIOAction);

View File

@ -30,11 +30,12 @@ protected:
int m_shapeType;
void* m_userPointer;
int m_userIndex;
int m_userIndex2;
public:
BT_DECLARE_ALIGNED_ALLOCATOR();
btCollisionShape() : m_shapeType(INVALID_SHAPE_PROXYTYPE), m_userPointer(0), m_userIndex(-1)
btCollisionShape() : m_shapeType(INVALID_SHAPE_PROXYTYPE), m_userPointer(0), m_userIndex(-1), m_userIndex2(-1)
{
}
@ -137,6 +138,16 @@ public:
return m_userIndex;
}
void setUserIndex2(int index)
{
m_userIndex2 = index;
}
int getUserIndex2() const
{
return m_userIndex2;
}
virtual int calculateSerializeBufferSize() const;
///fills the dataBuffer and returns the struct name (and 0 on failure)

View File

@ -263,7 +263,10 @@ void btDeformableBackwardEulerObjective::applyExplicitForce(TVStack& force)
{
for (int j = 0; j < psb->m_nodes.size(); ++j)
{
psb->m_nodes[j].m_effectiveMass_inv = psb->m_nodes[j].m_effectiveMass.inverse();
if (psb->m_nodes[j].m_im > 0)
{
psb->m_nodes[j].m_effectiveMass_inv = psb->m_nodes[j].m_effectiveMass.inverse();
}
}
}
}

View File

@ -3799,7 +3799,7 @@ void btSoftBody::interpolateRenderMesh()
const Node* p2 = m_renderNodesParents[i][2];
btVector3 normal = btCross(p1->m_x - p0->m_x, p2->m_x - p0->m_x);
btVector3 unit_normal = normal.normalized();
Node& n = m_renderNodes[i];
RenderNode& n = m_renderNodes[i];
n.m_x.setZero();
for (int j = 0; j < 3; ++j)
{
@ -3812,7 +3812,7 @@ void btSoftBody::interpolateRenderMesh()
{
for (int i = 0; i < m_renderNodes.size(); ++i)
{
Node& n = m_renderNodes[i];
RenderNode& n = m_renderNodes[i];
n.m_x.setZero();
for (int j = 0; j < 4; ++j)
{

View File

@ -258,6 +258,12 @@ public:
Material* m_material; // Material
};
/* Node */
struct RenderNode
{
btVector3 m_x;
btVector3 m_uv1;
btVector3 m_normal;
};
struct Node : Feature
{
btVector3 m_x; // Position
@ -290,6 +296,11 @@ public:
BT_DECLARE_ALIGNED_ALLOCATOR();
};
struct RenderFace
{
RenderNode* m_n[3]; // Node pointers
};
/* Face */
struct Face : Feature
{
@ -775,9 +786,11 @@ public:
typedef btAlignedObjectArray<Cluster*> tClusterArray;
typedef btAlignedObjectArray<Note> tNoteArray;
typedef btAlignedObjectArray<Node> tNodeArray;
typedef btAlignedObjectArray< RenderNode> tRenderNodeArray;
typedef btAlignedObjectArray<btDbvtNode*> tLeafArray;
typedef btAlignedObjectArray<Link> tLinkArray;
typedef btAlignedObjectArray<Face> tFaceArray;
typedef btAlignedObjectArray<RenderFace> tRenderFaceArray;
typedef btAlignedObjectArray<Tetra> tTetraArray;
typedef btAlignedObjectArray<Anchor> tAnchorArray;
typedef btAlignedObjectArray<RContact> tRContactArray;
@ -797,10 +810,10 @@ public:
btSoftBodyWorldInfo* m_worldInfo; // World info
tNoteArray m_notes; // Notes
tNodeArray m_nodes; // Nodes
tNodeArray m_renderNodes; // Nodes
tRenderNodeArray m_renderNodes; // Render Nodes
tLinkArray m_links; // Links
tFaceArray m_faces; // Faces
tFaceArray m_renderFaces; // Faces
tRenderFaceArray m_renderFaces; // Faces
tTetraArray m_tetras; // Tetras
btAlignedObjectArray<TetraScratch> m_tetraScratches;
btAlignedObjectArray<TetraScratch> m_tetraScratchesTn;

View File

@ -1296,6 +1296,7 @@ btSoftBody* btSoftBodyHelpers::CreateFromVtkFile(btSoftBodyWorldInfo& worldInfo,
position.setY(p);
ss >> p;
position.setZ(p);
//printf("v %f %f %f\n", position.getX(), position.getY(), position.getZ());
X[x_count++] = position;
}
else if (reading_tets)
@ -1314,9 +1315,9 @@ btSoftBody* btSoftBodyHelpers::CreateFromVtkFile(btSoftBodyWorldInfo& worldInfo,
for (size_t i = 0; i < 4; i++)
{
ss >> tet[i];
printf("%d ", tet[i]);
//printf("%d ", tet[i]);
}
printf("\n");
//printf("\n");
indices[indices_count++] = tet;
}
}
@ -1416,6 +1417,7 @@ void btSoftBodyHelpers::generateBoundaryFaces(btSoftBody* psb)
{
std::vector<int> f = it->second;
psb->appendFace(f[0], f[1], f[2]);
//printf("f %d %d %d\n", f[0] + 1, f[1] + 1, f[2] + 1);
}
}

View File

@ -100,6 +100,11 @@ void btSoftMultiBodyDynamicsWorld::internalSingleStepSimulation(btScalar timeSte
///update soft bodies
m_softBodySolver->updateSoftBodies();
for (int i = 0; i < m_softBodies.size(); i++)
{
btSoftBody* psb = (btSoftBody*)m_softBodies[i];
psb->interpolateRenderMesh();
}
// End solver-wise simulation step
// ///////////////////////////////
}