Preliminary working version of TinyRenderer for standalone demos,
it works without OpenGL dependency now, so it runs in the cloud :-) Add scaling support for TinyRenderer, remove some un-used normal mapping in TinyRenderer shader, expose light_dir_world, remove accidental hard-coded path in tga write_tga_file, Fix InverseDynamicsExampleCreateFunc, enum has to start at 0
This commit is contained in:
@@ -194,6 +194,7 @@
|
|||||||
include "../examples/HelloWorld"
|
include "../examples/HelloWorld"
|
||||||
include "../examples/BasicDemo"
|
include "../examples/BasicDemo"
|
||||||
include "../examples/InverseDynamics"
|
include "../examples/InverseDynamics"
|
||||||
|
include "../examples/ExtendedTutorials"
|
||||||
include "../examples/SharedMemory"
|
include "../examples/SharedMemory"
|
||||||
include "../examples/MultiThreading"
|
include "../examples/MultiThreading"
|
||||||
|
|
||||||
|
|||||||
@@ -101,3 +101,35 @@ if os.is("MacOSX") then
|
|||||||
links{"Cocoa.framework"}
|
links{"Cocoa.framework"}
|
||||||
end
|
end
|
||||||
|
|
||||||
|
|
||||||
|
project "App_BasicExampleTinyRenderer"
|
||||||
|
|
||||||
|
if _OPTIONS["ios"] then
|
||||||
|
kind "WindowedApp"
|
||||||
|
else
|
||||||
|
kind "ConsoleApp"
|
||||||
|
end
|
||||||
|
defines {"B3_USE_STANDALONE_EXAMPLE"}
|
||||||
|
|
||||||
|
includedirs {"../../src"}
|
||||||
|
|
||||||
|
links {
|
||||||
|
"BulletDynamics","BulletCollision", "LinearMath", "Bullet3Common"
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
language "C++"
|
||||||
|
|
||||||
|
files {
|
||||||
|
"BasicExample.cpp",
|
||||||
|
"*.h",
|
||||||
|
"../StandaloneMain/main_tinyrenderer_single_example.cpp",
|
||||||
|
"../ExampleBrowser/CollisionShape2TriangleMesh.cpp",
|
||||||
|
"../OpenGLWindow/SimpleCamera.cpp",
|
||||||
|
"../TinyRenderer/geometry.cpp",
|
||||||
|
"../TinyRenderer/model.cpp",
|
||||||
|
"../TinyRenderer/tgaimage.cpp",
|
||||||
|
"../TinyRenderer/our_gl.cpp",
|
||||||
|
"../TinyRenderer/TinyRenderer.cpp",
|
||||||
|
"../Utils/b3ResourcePath.cpp"
|
||||||
|
}
|
||||||
|
|||||||
@@ -42,7 +42,7 @@ struct RigidBodyFromObjExample : public CommonRigidBodyBase
|
|||||||
virtual void renderScene();
|
virtual void renderScene();
|
||||||
void resetCamera()
|
void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 41;
|
float dist = 11;
|
||||||
float pitch = 52;
|
float pitch = 52;
|
||||||
float yaw = 35;
|
float yaw = 35;
|
||||||
float targetPos[3]={0,0.46,0};
|
float targetPos[3]={0,0.46,0};
|
||||||
@@ -74,7 +74,7 @@ void RigidBodyFromObjExample::initPhysics()
|
|||||||
}
|
}
|
||||||
|
|
||||||
//load our obj mesh
|
//load our obj mesh
|
||||||
const char* fileName = "teddy.obj";//sphere8.obj";//sponza_closed.obj";//sphere8.obj";
|
const char* fileName = "textured_sphere_smooth.obj";//teddy.obj";//sphere8.obj";//sponza_closed.obj";//sphere8.obj";
|
||||||
char relativeFileName[1024];
|
char relativeFileName[1024];
|
||||||
if (b3ResourcePath::findResourcePath(fileName, relativeFileName, 1024))
|
if (b3ResourcePath::findResourcePath(fileName, relativeFileName, 1024))
|
||||||
{
|
{
|
||||||
@@ -88,7 +88,8 @@ void RigidBodyFromObjExample::initPhysics()
|
|||||||
const GLInstanceVertex& v = glmesh->m_vertices->at(0);
|
const GLInstanceVertex& v = glmesh->m_vertices->at(0);
|
||||||
btConvexHullShape* shape = new btConvexHullShape((const btScalar*)(&(v.xyzw[0])), glmesh->m_numvertices, sizeof(GLInstanceVertex));
|
btConvexHullShape* shape = new btConvexHullShape((const btScalar*)(&(v.xyzw[0])), glmesh->m_numvertices, sizeof(GLInstanceVertex));
|
||||||
|
|
||||||
shape->setLocalScaling(btVector3(0.1,0.1,0.1));
|
btVector3 localScaling(2,2,2);//0.1,0.1,0.1);
|
||||||
|
shape->setLocalScaling(localScaling);
|
||||||
|
|
||||||
if (m_options & OptimizeConvexObj)
|
if (m_options & OptimizeConvexObj)
|
||||||
{
|
{
|
||||||
@@ -114,25 +115,24 @@ void RigidBodyFromObjExample::initPhysics()
|
|||||||
if (isDynamic)
|
if (isDynamic)
|
||||||
shape->calculateLocalInertia(mass,localInertia);
|
shape->calculateLocalInertia(mass,localInertia);
|
||||||
|
|
||||||
btVector3 position(0,20,0);
|
btVector3 position(0,3,0);
|
||||||
startTransform.setOrigin(position);
|
startTransform.setOrigin(position);
|
||||||
btRigidBody* body = createRigidBody(mass,startTransform,shape);
|
btRigidBody* body = createRigidBody(mass,startTransform,shape);
|
||||||
|
|
||||||
btVector3 color(1,1,1);
|
btVector3 color(1,1,1);
|
||||||
btVector3 scaling(0.1,0.1,0.1);
|
|
||||||
bool useConvexHullForRendering = ((m_options & ObjUseConvexHullForRendering)!=0);
|
bool useConvexHullForRendering = ((m_options & ObjUseConvexHullForRendering)!=0);
|
||||||
|
|
||||||
|
|
||||||
if (!useConvexHullForRendering)
|
if (!useConvexHullForRendering)
|
||||||
{
|
{
|
||||||
int shapeId = m_guiHelper->getRenderInterface()->registerShape(&glmesh->m_vertices->at(0).xyzw[0],
|
int shapeId = m_guiHelper->registerGraphicsShape(&glmesh->m_vertices->at(0).xyzw[0],
|
||||||
glmesh->m_numvertices,
|
glmesh->m_numvertices,
|
||||||
&glmesh->m_indices->at(0),
|
&glmesh->m_indices->at(0),
|
||||||
glmesh->m_numIndices,
|
glmesh->m_numIndices);
|
||||||
B3_GL_TRIANGLES,-1);
|
shape->setUserIndex(shapeId);
|
||||||
shape->setUserIndex(shapeId);
|
int renderInstance = m_guiHelper->registerGraphicsInstance(shapeId,position,startTransform.getRotation(),color,localScaling);
|
||||||
int renderInstance = m_guiHelper->getRenderInterface()->registerGraphicsInstance(shapeId,position,startTransform.getRotation(),color,scaling);
|
body->setUserIndex(renderInstance);
|
||||||
body->setUserIndex(renderInstance);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
|
m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
|
||||||
@@ -155,5 +155,5 @@ CommonExampleInterface* ET_RigidBodyFromObjCreateFunc(CommonExampleOptions& o
|
|||||||
return new RigidBodyFromObjExample(options.m_guiHelper,options.m_option);
|
return new RigidBodyFromObjExample(options.m_guiHelper,options.m_option);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
B3_STANDALONE_EXAMPLE(ET_RigidBodyFromObjCreateFunc)
|
||||||
|
|
||||||
|
|||||||
222
examples/ExtendedTutorials/premake4.lua
Normal file
222
examples/ExtendedTutorials/premake4.lua
Normal file
@@ -0,0 +1,222 @@
|
|||||||
|
|
||||||
|
project "App_RigidBodyFromObjExample"
|
||||||
|
|
||||||
|
if _OPTIONS["ios"] then
|
||||||
|
kind "WindowedApp"
|
||||||
|
else
|
||||||
|
kind "ConsoleApp"
|
||||||
|
end
|
||||||
|
defines {"B3_USE_STANDALONE_EXAMPLE"}
|
||||||
|
includedirs {"../../src"}
|
||||||
|
|
||||||
|
links {
|
||||||
|
"BulletInverseDynamicsUtils", "BulletInverseDynamics","Bullet3Common","BulletDynamics","BulletCollision", "LinearMath"
|
||||||
|
}
|
||||||
|
|
||||||
|
language "C++"
|
||||||
|
|
||||||
|
files {
|
||||||
|
"RigidBodyFromObj.cpp",
|
||||||
|
"**.h",
|
||||||
|
"../StandaloneMain/main_console_single_example.cpp",
|
||||||
|
"../Utils/b3ResourcePath.cpp",
|
||||||
|
"../Utils/b3ResourcePath.h",
|
||||||
|
"../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/Wavefront/tiny_obj_loader.cpp",
|
||||||
|
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.h",
|
||||||
|
"../Importers/ImportColladaDemo/LoadMeshFromCollada.cpp",
|
||||||
|
"../Importers/ImportObjDemo/LoadMeshFromObj.cpp",
|
||||||
|
"../Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/BulletUrdfImporter.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/MyMultiBodyCreator.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/URDF2Bullet.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/UrdfParser.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/urdfStringSplit.cpp",
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
project "App_RigidBodyFromObjExampleGui"
|
||||||
|
|
||||||
|
if _OPTIONS["ios"] then
|
||||||
|
kind "WindowedApp"
|
||||||
|
else
|
||||||
|
kind "ConsoleApp"
|
||||||
|
end
|
||||||
|
defines {"B3_USE_STANDALONE_EXAMPLE"}
|
||||||
|
|
||||||
|
includedirs {"../../src"}
|
||||||
|
|
||||||
|
links {
|
||||||
|
"BulletInverseDynamicsUtils", "BulletInverseDynamics","BulletDynamics","BulletCollision", "LinearMath", "OpenGL_Window","Bullet3Common"
|
||||||
|
}
|
||||||
|
|
||||||
|
initOpenGL()
|
||||||
|
initGlew()
|
||||||
|
|
||||||
|
|
||||||
|
language "C++"
|
||||||
|
|
||||||
|
files {
|
||||||
|
"RigidBodyFromObj.cpp",
|
||||||
|
"*.h",
|
||||||
|
"../StandaloneMain/main_opengl_single_example.cpp",
|
||||||
|
"../ExampleBrowser/OpenGLGuiHelper.cpp",
|
||||||
|
"../ExampleBrowser/GL_ShapeDrawer.cpp",
|
||||||
|
"../ExampleBrowser/CollisionShape2TriangleMesh.cpp",
|
||||||
|
"../Utils/b3ResourcePath.cpp",
|
||||||
|
"../Utils/b3ResourcePath.h",
|
||||||
|
"../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/Wavefront/tiny_obj_loader.cpp",
|
||||||
|
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.h",
|
||||||
|
"../Importers/ImportColladaDemo/LoadMeshFromCollada.cpp",
|
||||||
|
"../Importers/ImportObjDemo/LoadMeshFromObj.cpp",
|
||||||
|
"../Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/BulletUrdfImporter.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/MyMultiBodyCreator.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/URDF2Bullet.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/UrdfParser.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/urdfStringSplit.cpp",
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if os.is("Linux") then initX11() end
|
||||||
|
|
||||||
|
if os.is("MacOSX") then
|
||||||
|
links{"Cocoa.framework"}
|
||||||
|
end
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
project "App_RigidBodyFromObjExampleGuiWithSoftwareRenderer"
|
||||||
|
|
||||||
|
if _OPTIONS["ios"] then
|
||||||
|
kind "WindowedApp"
|
||||||
|
else
|
||||||
|
kind "ConsoleApp"
|
||||||
|
end
|
||||||
|
defines {"B3_USE_STANDALONE_EXAMPLE"}
|
||||||
|
|
||||||
|
includedirs {"../../src"}
|
||||||
|
|
||||||
|
links {
|
||||||
|
"BulletInverseDynamicsUtils", "BulletInverseDynamics","BulletDynamics","BulletCollision", "LinearMath", "OpenGL_Window","Bullet3Common"
|
||||||
|
}
|
||||||
|
|
||||||
|
initOpenGL()
|
||||||
|
initGlew()
|
||||||
|
|
||||||
|
|
||||||
|
language "C++"
|
||||||
|
|
||||||
|
files {
|
||||||
|
"RigidBodyFromObj.cpp",
|
||||||
|
"*.h",
|
||||||
|
"../StandaloneMain/main_sw_tinyrenderer_single_example.cpp",
|
||||||
|
"../ExampleBrowser/OpenGLGuiHelper.cpp",
|
||||||
|
"../ExampleBrowser/GL_ShapeDrawer.cpp",
|
||||||
|
"../ExampleBrowser/CollisionShape2TriangleMesh.cpp",
|
||||||
|
"../TinyRenderer/geometry.cpp",
|
||||||
|
"../TinyRenderer/model.cpp",
|
||||||
|
"../TinyRenderer/tgaimage.cpp",
|
||||||
|
"../TinyRenderer/our_gl.cpp",
|
||||||
|
"../TinyRenderer/TinyRenderer.cpp",
|
||||||
|
"../Utils/b3ResourcePath.cpp",
|
||||||
|
"../Utils/b3ResourcePath.cpp",
|
||||||
|
"../Utils/b3ResourcePath.h",
|
||||||
|
"../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/Wavefront/tiny_obj_loader.cpp",
|
||||||
|
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.h",
|
||||||
|
"../Importers/ImportColladaDemo/LoadMeshFromCollada.cpp",
|
||||||
|
"../Importers/ImportObjDemo/LoadMeshFromObj.cpp",
|
||||||
|
"../Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/BulletUrdfImporter.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/MyMultiBodyCreator.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/URDF2Bullet.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/UrdfParser.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/urdfStringSplit.cpp",
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if os.is("Linux") then initX11() end
|
||||||
|
|
||||||
|
if os.is("MacOSX") then
|
||||||
|
links{"Cocoa.framework"}
|
||||||
|
end
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
project "App_RigidBodyFromObjExampleTinyRenderer"
|
||||||
|
|
||||||
|
if _OPTIONS["ios"] then
|
||||||
|
kind "WindowedApp"
|
||||||
|
else
|
||||||
|
kind "ConsoleApp"
|
||||||
|
end
|
||||||
|
defines {"B3_USE_STANDALONE_EXAMPLE"}
|
||||||
|
|
||||||
|
includedirs {"../../bsrc"}
|
||||||
|
|
||||||
|
links {
|
||||||
|
"BulletInverseDynamicsUtils", "BulletInverseDynamics","BulletDynamics","BulletCollision", "LinearMath", "Bullet3Common"
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
language "C++"
|
||||||
|
|
||||||
|
files {
|
||||||
|
"RigidBodyFromObj.cpp",
|
||||||
|
"*.h",
|
||||||
|
"../StandaloneMain/main_tinyrenderer_single_example.cpp",
|
||||||
|
"../OpenGLWindow/SimpleCamera.cpp",
|
||||||
|
"../ExampleBrowser/CollisionShape2TriangleMesh.cpp",
|
||||||
|
"../TinyRenderer/geometry.cpp",
|
||||||
|
"../TinyRenderer/model.cpp",
|
||||||
|
"../TinyRenderer/tgaimage.cpp",
|
||||||
|
"../TinyRenderer/our_gl.cpp",
|
||||||
|
"../TinyRenderer/TinyRenderer.cpp",
|
||||||
|
"../Utils/b3ResourcePath.cpp",
|
||||||
|
"../Utils/b3ResourcePath.cpp",
|
||||||
|
"../Utils/b3ResourcePath.h",
|
||||||
|
"../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/Wavefront/tiny_obj_loader.cpp",
|
||||||
|
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.h",
|
||||||
|
"../Importers/ImportColladaDemo/LoadMeshFromCollada.cpp",
|
||||||
|
"../Importers/ImportObjDemo/LoadMeshFromObj.cpp",
|
||||||
|
"../Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/BulletUrdfImporter.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/MyMultiBodyCreator.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/URDF2Bullet.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/UrdfParser.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/urdfStringSplit.cpp",
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
@@ -87,10 +87,10 @@ public:
|
|||||||
|
|
||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 3.5;
|
float dist = 1.5;
|
||||||
float pitch = -136;
|
float pitch = -80;
|
||||||
float yaw = 28;
|
float yaw = 10;
|
||||||
float targetPos[3]={0.47,0,-0.64};
|
float targetPos[3]={0,0,0};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
@@ -239,7 +239,7 @@ void InverseDynamicsExample::initPhysics()
|
|||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -18,8 +18,8 @@ subject to the following restrictions:
|
|||||||
|
|
||||||
enum btInverseDynamicsExampleOptions
|
enum btInverseDynamicsExampleOptions
|
||||||
{
|
{
|
||||||
BT_ID_LOAD_URDF=1,
|
BT_ID_LOAD_URDF=0,
|
||||||
BT_ID_PROGRAMMATICALLY=2
|
BT_ID_PROGRAMMATICALLY=1
|
||||||
};
|
};
|
||||||
|
|
||||||
class CommonExampleInterface* InverseDynamicsExampleCreateFunc(struct CommonExampleOptions& options);
|
class CommonExampleInterface* InverseDynamicsExampleCreateFunc(struct CommonExampleOptions& options);
|
||||||
|
|||||||
@@ -165,3 +165,56 @@ if os.is("MacOSX") then
|
|||||||
links{"Cocoa.framework"}
|
links{"Cocoa.framework"}
|
||||||
end
|
end
|
||||||
|
|
||||||
|
|
||||||
|
project "App_InverseDynamicsExampleTinyRenderer"
|
||||||
|
|
||||||
|
if _OPTIONS["ios"] then
|
||||||
|
kind "WindowedApp"
|
||||||
|
else
|
||||||
|
kind "ConsoleApp"
|
||||||
|
end
|
||||||
|
defines {"B3_USE_STANDALONE_EXAMPLE"}
|
||||||
|
|
||||||
|
includedirs {"../../src"}
|
||||||
|
|
||||||
|
links {
|
||||||
|
"BulletInverseDynamicsUtils", "BulletInverseDynamics","BulletDynamics","BulletCollision", "LinearMath", "Bullet3Common"
|
||||||
|
}
|
||||||
|
|
||||||
|
language "C++"
|
||||||
|
|
||||||
|
files {
|
||||||
|
"InverseDynamicsExample.cpp",
|
||||||
|
"*.h",
|
||||||
|
"../StandaloneMain/main_tinyrenderer_single_example.cpp",
|
||||||
|
"../OpenGLWindow/SimpleCamera.cpp",
|
||||||
|
"../ExampleBrowser/CollisionShape2TriangleMesh.cpp",
|
||||||
|
"../TinyRenderer/geometry.cpp",
|
||||||
|
"../TinyRenderer/model.cpp",
|
||||||
|
"../TinyRenderer/tgaimage.cpp",
|
||||||
|
"../TinyRenderer/our_gl.cpp",
|
||||||
|
"../TinyRenderer/TinyRenderer.cpp",
|
||||||
|
"../Utils/b3ResourcePath.cpp",
|
||||||
|
"../Utils/b3ResourcePath.cpp",
|
||||||
|
"../Utils/b3ResourcePath.h",
|
||||||
|
"../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/Wavefront/tiny_obj_loader.cpp",
|
||||||
|
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.h",
|
||||||
|
"../Importers/ImportColladaDemo/LoadMeshFromCollada.cpp",
|
||||||
|
"../Importers/ImportObjDemo/LoadMeshFromObj.cpp",
|
||||||
|
"../Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/BulletUrdfImporter.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/MyMultiBodyCreator.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/URDF2Bullet.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/UrdfParser.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/urdfStringSplit.cpp",
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -125,6 +125,16 @@ struct TinyRendererSetup : public CommonExampleInterface
|
|||||||
{
|
{
|
||||||
m_useSoftware = (rendererIndex==0);
|
m_useSoftware = (rendererIndex==0);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void resetCamera()
|
||||||
|
{
|
||||||
|
float dist = 11;
|
||||||
|
float pitch = 52;
|
||||||
|
float yaw = 35;
|
||||||
|
float targetPos[3]={0,0.46,0};
|
||||||
|
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
@@ -335,13 +345,20 @@ void TinyRendererSetup::stepSimulation(float deltaTime)
|
|||||||
m_internalData->m_renderObjects[o]->m_viewMatrix[i][j] = viewMat[i+4*j];
|
m_internalData->m_renderObjects[o]->m_viewMatrix[i][j] = viewMat[i+4*j];
|
||||||
m_internalData->m_renderObjects[o]->m_projectionMatrix[i][j] = projMat[i+4*j];
|
m_internalData->m_renderObjects[o]->m_projectionMatrix[i][j] = projMat[i+4*j];
|
||||||
|
|
||||||
float eye[4];
|
btVector3 lightDirWorld;
|
||||||
float center[4];
|
switch (m_app->getUpAxis())
|
||||||
render->getActiveCamera()->getCameraPosition(eye);
|
{
|
||||||
render->getActiveCamera()->getCameraTargetPosition(center);
|
case 1:
|
||||||
|
lightDirWorld = btVector3(-50.f,100,30);
|
||||||
m_internalData->m_renderObjects[o]->m_eye.setValue(eye[0],eye[1],eye[2]);
|
break;
|
||||||
m_internalData->m_renderObjects[o]->m_center.setValue(center[0],center[1],center[2]);
|
case 2:
|
||||||
|
lightDirWorld = btVector3(-50.f,30,100);
|
||||||
|
break;
|
||||||
|
default:{}
|
||||||
|
};
|
||||||
|
|
||||||
|
m_internalData->m_renderObjects[o]->m_lightDirWorld = lightDirWorld.normalized();
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
TinyRenderer::renderObject(*m_internalData->m_renderObjects[o]);
|
TinyRenderer::renderObject(*m_internalData->m_renderObjects[o]);
|
||||||
|
|||||||
@@ -150,10 +150,27 @@ public:
|
|||||||
|
|
||||||
ATTRIBUTE_ALIGNED16(float modelMat[16]);
|
ATTRIBUTE_ALIGNED16(float modelMat[16]);
|
||||||
ATTRIBUTE_ALIGNED16(float viewMat[16]);
|
ATTRIBUTE_ALIGNED16(float viewMat[16]);
|
||||||
|
ATTRIBUTE_ALIGNED16(float projMat[16]);
|
||||||
|
|
||||||
CommonRenderInterface* render = getRenderInterface();
|
CommonRenderInterface* render = getRenderInterface();
|
||||||
|
|
||||||
|
render->getActiveCamera()->getCameraProjectionMatrix(projMat);
|
||||||
render->getActiveCamera()->getCameraViewMatrix(viewMat);
|
render->getActiveCamera()->getCameraViewMatrix(viewMat);
|
||||||
|
|
||||||
|
btVector3 lightDirWorld(-5,200,-40);
|
||||||
|
switch (1)//app->getUpAxis())
|
||||||
|
{
|
||||||
|
case 1:
|
||||||
|
lightDirWorld = btVector3(-50.f,100,30);
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
lightDirWorld = btVector3(-50.f,30,100);
|
||||||
|
break;
|
||||||
|
default:{}
|
||||||
|
};
|
||||||
|
|
||||||
|
lightDirWorld.normalize();
|
||||||
|
|
||||||
|
|
||||||
for (int i=0;i<rbWorld->getNumCollisionObjects();i++)
|
for (int i=0;i<rbWorld->getNumCollisionObjects();i++)
|
||||||
{
|
{
|
||||||
@@ -173,21 +190,25 @@ public:
|
|||||||
if (sptr)
|
if (sptr)
|
||||||
{
|
{
|
||||||
renderObj = *sptr;
|
renderObj = *sptr;
|
||||||
}
|
//sync the object transform
|
||||||
}
|
const btTransform& tr = colObj->getWorldTransform();
|
||||||
//sync the object transform
|
tr.getOpenGLMatrix(modelMat);
|
||||||
const btTransform& tr = colObj->getWorldTransform();
|
|
||||||
tr.getOpenGLMatrix(modelMat);
|
|
||||||
|
|
||||||
for (int i=0;i<4;i++)
|
for (int i=0;i<4;i++)
|
||||||
{
|
{
|
||||||
for (int j=0;j<4;j++)
|
for (int j=0;j<4;j++)
|
||||||
{
|
{
|
||||||
renderObj->m_modelMatrix[i][j] = modelMat[i+4*j];
|
|
||||||
renderObj->m_viewMatrix[i][j] = viewMat[i+4*j];
|
renderObj->m_projectionMatrix[i][j] = projMat[i+4*j];
|
||||||
|
renderObj->m_modelMatrix[i][j] = modelMat[i+4*j];
|
||||||
|
renderObj->m_viewMatrix[i][j] = viewMat[i+4*j];
|
||||||
|
renderObj->m_localScaling = colObj->getCollisionShape()->getLocalScaling();
|
||||||
|
renderObj->m_lightDirWorld = lightDirWorld;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
TinyRenderer::renderObject(*renderObj);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
TinyRenderer::renderObject(*renderObj);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -210,10 +231,12 @@ public:
|
|||||||
|
|
||||||
static int counter=0;
|
static int counter=0;
|
||||||
counter++;
|
counter++;
|
||||||
if (counter>10)
|
if ((counter&7)==0)
|
||||||
{
|
{
|
||||||
counter=0;
|
|
||||||
getFrameBuffer().write_tga_file("/Users/erwincoumans/develop/bullet3/framebuf.tga",true);
|
char filename[1024];
|
||||||
|
sprintf(filename,"framebuf%d.tga",counter);
|
||||||
|
getFrameBuffer().write_tga_file(filename,true);
|
||||||
}
|
}
|
||||||
float color[4] = {1,1,1,1};
|
float color[4] = {1,1,1,1};
|
||||||
m_primRenderer->drawTexturedRect(0,0,m_swWidth, m_swHeight,color,0,0,1,1,true);
|
m_primRenderer->drawTexturedRect(0,0,m_swWidth, m_swHeight,color,0,0,1,1,true);
|
||||||
|
|||||||
365
examples/StandaloneMain/main_tinyrenderer_single_example.cpp
Normal file
365
examples/StandaloneMain/main_tinyrenderer_single_example.cpp
Normal file
@@ -0,0 +1,365 @@
|
|||||||
|
/*
|
||||||
|
Bullet Continuous Collision Detection and Physics Library
|
||||||
|
Copyright (c) 2015 Google Inc. http://bulletphysics.org
|
||||||
|
|
||||||
|
This software is provided 'as-is', without any express or implied warranty.
|
||||||
|
In no event will the authors be held liable for any damages arising from the use of this software.
|
||||||
|
Permission is granted to anyone to use this software for any purpose,
|
||||||
|
including commercial applications, and to alter it and redistribute it freely,
|
||||||
|
subject to the following restrictions:
|
||||||
|
|
||||||
|
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
|
||||||
|
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
|
||||||
|
3. This notice may not be removed or altered from any source distribution.
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#include "../CommonInterfaces/CommonExampleInterface.h"
|
||||||
|
#include "../CommonInterfaces/CommonGUIHelperInterface.h"
|
||||||
|
#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
|
||||||
|
#include "BulletCollision/CollisionShapes/btCollisionShape.h"
|
||||||
|
#include "BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h"
|
||||||
|
#include "../ExampleBrowser/CollisionShape2TriangleMesh.h"
|
||||||
|
#include "../OpenGLWindow/GLInstanceGraphicsShape.h"
|
||||||
|
#include "LinearMath/btTransform.h"
|
||||||
|
#include "LinearMath/btHashMap.h"
|
||||||
|
|
||||||
|
#include "../TinyRenderer/TinyRenderer.h"
|
||||||
|
#include "../OpenGLWindow/SimpleCamera.h"
|
||||||
|
|
||||||
|
static btVector4 sMyColors[4] =
|
||||||
|
{
|
||||||
|
btVector4(0.3,0.3,1,1),
|
||||||
|
btVector4(0.6,0.6,1,1),
|
||||||
|
btVector4(0,1,0,1),
|
||||||
|
btVector4(0,1,1,1),
|
||||||
|
//btVector4(1,1,0,1),
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
struct TinyRendererGUIHelper : public GUIHelperInterface
|
||||||
|
{
|
||||||
|
|
||||||
|
int m_upAxis;
|
||||||
|
|
||||||
|
btHashMap<btHashInt,TinyRenderObjectData*> m_swRenderObjects;
|
||||||
|
btHashMap<btHashInt,int> m_swInstances;
|
||||||
|
|
||||||
|
int m_swWidth;
|
||||||
|
int m_swHeight;
|
||||||
|
TGAImage m_rgbColorBuffer;
|
||||||
|
|
||||||
|
b3AlignedObjectArray<float> m_depthBuffer;
|
||||||
|
|
||||||
|
SimpleCamera m_camera;
|
||||||
|
int m_colObjUniqueIndex;
|
||||||
|
|
||||||
|
TinyRendererGUIHelper( int swWidth, int swHeight)
|
||||||
|
: m_upAxis(1),
|
||||||
|
m_swWidth(swWidth),
|
||||||
|
m_swHeight(swHeight),
|
||||||
|
m_rgbColorBuffer(swWidth,swHeight,TGAImage::RGB),
|
||||||
|
m_colObjUniqueIndex(0)
|
||||||
|
{
|
||||||
|
m_depthBuffer.resize(swWidth*swHeight);
|
||||||
|
}
|
||||||
|
|
||||||
|
void clearBuffers(TGAColor& clearColor)
|
||||||
|
{
|
||||||
|
for(int y=0;y<m_swHeight;++y)
|
||||||
|
{
|
||||||
|
for(int x=0;x<m_swWidth;++x)
|
||||||
|
{
|
||||||
|
m_rgbColorBuffer.set(x,y,clearColor);
|
||||||
|
m_depthBuffer[x+y*m_swWidth] = -1e30f;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
const TGAImage& getFrameBuffer() const
|
||||||
|
{
|
||||||
|
return m_rgbColorBuffer;
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual ~TinyRendererGUIHelper()
|
||||||
|
{
|
||||||
|
for (int i=0;i<m_swRenderObjects.size();i++)
|
||||||
|
{
|
||||||
|
TinyRenderObjectData** d = m_swRenderObjects[i];
|
||||||
|
if (d && *d)
|
||||||
|
{
|
||||||
|
delete *d;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
virtual void createRigidBodyGraphicsObject(btRigidBody* body,const btVector3& color){}
|
||||||
|
|
||||||
|
virtual void createCollisionObjectGraphicsObject(btCollisionObject* obj,const btVector3& color)
|
||||||
|
{
|
||||||
|
if (obj->getUserIndex()<0)
|
||||||
|
{
|
||||||
|
int colIndex = m_colObjUniqueIndex++;
|
||||||
|
obj->setUserIndex(colIndex);
|
||||||
|
int shapeIndex = obj->getCollisionShape()->getUserIndex();
|
||||||
|
|
||||||
|
if (colIndex>=0 && shapeIndex>=0)
|
||||||
|
{
|
||||||
|
m_swInstances.insert(colIndex,shapeIndex);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual void createCollisionShapeGraphicsObject(btCollisionShape* collisionShape)
|
||||||
|
{
|
||||||
|
//already has a graphics object?
|
||||||
|
if (collisionShape->getUserIndex()>=0)
|
||||||
|
return;
|
||||||
|
|
||||||
|
|
||||||
|
btAlignedObjectArray<GLInstanceVertex> gfxVertices;
|
||||||
|
|
||||||
|
btAlignedObjectArray<int> indices;
|
||||||
|
btTransform startTrans;startTrans.setIdentity();
|
||||||
|
|
||||||
|
{
|
||||||
|
btAlignedObjectArray<btVector3> vertexPositions;
|
||||||
|
btAlignedObjectArray<btVector3> vertexNormals;
|
||||||
|
CollisionShape2TriangleMesh(collisionShape,startTrans,vertexPositions,vertexNormals,indices);
|
||||||
|
gfxVertices.resize(vertexPositions.size());
|
||||||
|
for (int i=0;i<vertexPositions.size();i++)
|
||||||
|
{
|
||||||
|
for (int j=0;j<4;j++)
|
||||||
|
{
|
||||||
|
gfxVertices[i].xyzw[j] = vertexPositions[i][j];
|
||||||
|
}
|
||||||
|
for (int j=0;j<3;j++)
|
||||||
|
{
|
||||||
|
gfxVertices[i].normal[j] = vertexNormals[i][j];
|
||||||
|
}
|
||||||
|
for (int j=0;j<2;j++)
|
||||||
|
{
|
||||||
|
gfxVertices[i].uv[j] = 0.5;//we don't have UV info...
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
if (gfxVertices.size() && indices.size())
|
||||||
|
{
|
||||||
|
int shapeId = registerGraphicsShape(&gfxVertices[0].xyzw[0],gfxVertices.size(),&indices[0],indices.size());
|
||||||
|
collisionShape->setUserIndex(shapeId);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual void syncPhysicsToGraphics(const btDiscreteDynamicsWorld* rbWorld){}
|
||||||
|
|
||||||
|
virtual void render(const btDiscreteDynamicsWorld* rbWorld)
|
||||||
|
{
|
||||||
|
//clear the color buffer
|
||||||
|
TGAColor clearColor;
|
||||||
|
clearColor.bgra[0] = 255;
|
||||||
|
clearColor.bgra[1] = 255;
|
||||||
|
clearColor.bgra[2] = 255;
|
||||||
|
clearColor.bgra[3] = 255;
|
||||||
|
|
||||||
|
clearBuffers(clearColor);
|
||||||
|
|
||||||
|
|
||||||
|
ATTRIBUTE_ALIGNED16(float modelMat[16]);
|
||||||
|
ATTRIBUTE_ALIGNED16(float viewMat[16]);
|
||||||
|
ATTRIBUTE_ALIGNED16(float projMat[16]);
|
||||||
|
|
||||||
|
m_camera.getCameraProjectionMatrix(projMat);
|
||||||
|
m_camera.getCameraViewMatrix(viewMat);
|
||||||
|
|
||||||
|
btVector3 lightDirWorld(-5,200,-40);
|
||||||
|
switch (1)//app->getUpAxis())
|
||||||
|
{
|
||||||
|
case 1:
|
||||||
|
lightDirWorld = btVector3(-50.f,100,30);
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
lightDirWorld = btVector3(-50.f,30,100);
|
||||||
|
break;
|
||||||
|
default:{}
|
||||||
|
};
|
||||||
|
|
||||||
|
lightDirWorld.normalize();
|
||||||
|
|
||||||
|
|
||||||
|
for (int i=0;i<rbWorld->getNumCollisionObjects();i++)
|
||||||
|
{
|
||||||
|
btCollisionObject* colObj = rbWorld->getCollisionObjectArray()[i];
|
||||||
|
int colObjIndex = colObj->getUserIndex();
|
||||||
|
int shapeIndex = colObj->getCollisionShape()->getUserIndex();
|
||||||
|
if (colObjIndex>=0 && shapeIndex>=0)
|
||||||
|
{
|
||||||
|
|
||||||
|
TinyRenderObjectData* renderObj = 0;
|
||||||
|
|
||||||
|
int* cptr = m_swInstances[colObjIndex];
|
||||||
|
if (cptr)
|
||||||
|
{
|
||||||
|
int c = *cptr;
|
||||||
|
TinyRenderObjectData** sptr = m_swRenderObjects[c];
|
||||||
|
if (sptr)
|
||||||
|
{
|
||||||
|
renderObj = *sptr;
|
||||||
|
//sync the object transform
|
||||||
|
const btTransform& tr = colObj->getWorldTransform();
|
||||||
|
tr.getOpenGLMatrix(modelMat);
|
||||||
|
|
||||||
|
for (int i=0;i<4;i++)
|
||||||
|
{
|
||||||
|
for (int j=0;j<4;j++)
|
||||||
|
{
|
||||||
|
|
||||||
|
renderObj->m_projectionMatrix[i][j] = projMat[i+4*j];
|
||||||
|
renderObj->m_modelMatrix[i][j] = modelMat[i+4*j];
|
||||||
|
renderObj->m_viewMatrix[i][j] = viewMat[i+4*j];
|
||||||
|
renderObj->m_localScaling = colObj->getCollisionShape()->getLocalScaling();
|
||||||
|
renderObj->m_lightDirWorld = lightDirWorld;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
TinyRenderer::renderObject(*renderObj);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
static int counter=0;
|
||||||
|
counter++;
|
||||||
|
if ((counter&7)==0)
|
||||||
|
{
|
||||||
|
|
||||||
|
char filename[1024];
|
||||||
|
sprintf(filename,"framebuf%d.tga",counter);
|
||||||
|
m_rgbColorBuffer.flip_vertically();
|
||||||
|
getFrameBuffer().write_tga_file(filename,true);
|
||||||
|
}
|
||||||
|
float color[4] = {1,1,1,1};
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual void createPhysicsDebugDrawer( btDiscreteDynamicsWorld* rbWorld){}
|
||||||
|
|
||||||
|
virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices)
|
||||||
|
{
|
||||||
|
int shapeIndex = m_swRenderObjects.size();
|
||||||
|
|
||||||
|
TinyRenderObjectData* swObj = new TinyRenderObjectData(m_swWidth,m_swHeight,m_rgbColorBuffer,m_depthBuffer);
|
||||||
|
swObj->registerMeshShape(vertices,numvertices,indices,numIndices);
|
||||||
|
//swObj->createCube(1,1,1);//MeshShape(vertices,numvertices,indices,numIndices);
|
||||||
|
m_swRenderObjects.insert(shapeIndex,swObj);
|
||||||
|
return shapeIndex;
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual int registerGraphicsInstance(int shapeIndex, const float* position, const float* quaternion, const float* color, const float* scaling)
|
||||||
|
{
|
||||||
|
int colIndex = m_colObjUniqueIndex++;
|
||||||
|
|
||||||
|
if (colIndex>=0 && shapeIndex>=0)
|
||||||
|
{
|
||||||
|
TinyRenderObjectData** dPtr = m_swRenderObjects[shapeIndex];
|
||||||
|
if (dPtr && *dPtr)
|
||||||
|
{
|
||||||
|
TinyRenderObjectData* d= *dPtr;
|
||||||
|
d->m_localScaling.setValue(scaling[0],scaling[1],scaling[2]);
|
||||||
|
m_swInstances.insert(colIndex,shapeIndex);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return colIndex;
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual Common2dCanvasInterface* get2dCanvasInterface()
|
||||||
|
{
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual CommonParameterInterface* getParameterInterface()
|
||||||
|
{
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual CommonRenderInterface* getRenderInterface()
|
||||||
|
{
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual CommonGraphicsApp* getAppInterface()
|
||||||
|
{
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
virtual void setUpAxis(int axis)
|
||||||
|
{
|
||||||
|
m_upAxis = axis;
|
||||||
|
m_camera.setCameraUpAxis(axis);
|
||||||
|
m_camera.update();
|
||||||
|
}
|
||||||
|
virtual void resetCamera(float camDist, float pitch, float yaw, float camPosX,float camPosY, float camPosZ)
|
||||||
|
{
|
||||||
|
m_camera.setCameraDistance(camDist);
|
||||||
|
m_camera.setCameraPitch(pitch);
|
||||||
|
m_camera.setCameraYaw(yaw);
|
||||||
|
m_camera.setCameraTargetPosition(camPosX,camPosY,camPosZ);
|
||||||
|
m_camera.setAspectRatio((float)m_swWidth/(float)m_swHeight);
|
||||||
|
m_camera.update();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual void autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld)
|
||||||
|
{
|
||||||
|
|
||||||
|
for (int i=0;i<rbWorld->getNumCollisionObjects();i++)
|
||||||
|
{
|
||||||
|
btCollisionObject* colObj = rbWorld->getCollisionObjectArray()[i];
|
||||||
|
//btRigidBody* body = btRigidBody::upcast(colObj);
|
||||||
|
//does this also work for btMultiBody/btMultiBodyLinkCollider?
|
||||||
|
createCollisionShapeGraphicsObject(colObj->getCollisionShape());
|
||||||
|
int colorIndex = colObj->getBroadphaseHandle()->getUid() & 3;
|
||||||
|
|
||||||
|
btVector3 color= sMyColors[colorIndex];
|
||||||
|
createCollisionObjectGraphicsObject(colObj,color);
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual void drawText3D( const char* txt, float posX, float posZY, float posZ, float size)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
int main(int argc, char* argv[])
|
||||||
|
{
|
||||||
|
|
||||||
|
TinyRendererGUIHelper noGfx(640,480);
|
||||||
|
|
||||||
|
CommonExampleOptions options(&noGfx);
|
||||||
|
CommonExampleInterface* example = StandaloneExampleCreateFunc(options);
|
||||||
|
|
||||||
|
example->initPhysics();
|
||||||
|
example->resetCamera();
|
||||||
|
|
||||||
|
for (int i=0;i<1000;i++)
|
||||||
|
{
|
||||||
|
printf("Simulating step %d\n",i);
|
||||||
|
example->stepSimulation(1.f/60.f);
|
||||||
|
example->renderScene();
|
||||||
|
}
|
||||||
|
example->exitPhysics();
|
||||||
|
|
||||||
|
delete example;
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
@@ -12,7 +12,7 @@
|
|||||||
#include "../OpenGLWindow/ShapeData.h"
|
#include "../OpenGLWindow/ShapeData.h"
|
||||||
#include "LinearMath/btAlignedObjectArray.h"
|
#include "LinearMath/btAlignedObjectArray.h"
|
||||||
#include "LinearMath/btVector3.h"
|
#include "LinearMath/btVector3.h"
|
||||||
Vec3f light_dir_world(1,1,1);
|
Vec3f light_dir_world(0,0,0);
|
||||||
|
|
||||||
|
|
||||||
struct Shader : public IShader {
|
struct Shader : public IShader {
|
||||||
@@ -22,18 +22,20 @@ struct Shader : public IShader {
|
|||||||
Matrix& m_modelMat;
|
Matrix& m_modelMat;
|
||||||
Matrix& m_modelView1;
|
Matrix& m_modelView1;
|
||||||
Matrix& m_projectionMatrix;
|
Matrix& m_projectionMatrix;
|
||||||
|
Vec3f m_localScaling;
|
||||||
|
|
||||||
mat<2,3,float> varying_uv; // triangle uv coordinates, written by the vertex shader, read by the fragment shader
|
mat<2,3,float> varying_uv; // triangle uv coordinates, written by the vertex shader, read by the fragment shader
|
||||||
mat<4,3,float> varying_tri; // triangle coordinates (clip coordinates), written by VS, read by FS
|
mat<4,3,float> varying_tri; // triangle coordinates (clip coordinates), written by VS, read by FS
|
||||||
mat<3,3,float> varying_nrm; // normal per vertex to be interpolated by FS
|
mat<3,3,float> varying_nrm; // normal per vertex to be interpolated by FS
|
||||||
mat<3,3,float> ndc_tri; // triangle in normalized device coordinates
|
//mat<3,3,float> ndc_tri; // triangle in normalized device coordinates
|
||||||
|
|
||||||
Shader(Model* model, Vec3f light_dir_local, Matrix& modelView, Matrix& projectionMatrix, Matrix& modelMat)
|
Shader(Model* model, Vec3f light_dir_local, Matrix& modelView, Matrix& projectionMatrix, Matrix& modelMat, Vec3f localScaling)
|
||||||
:m_model(model),
|
:m_model(model),
|
||||||
m_light_dir_local(light_dir_local),
|
m_light_dir_local(light_dir_local),
|
||||||
m_modelView1(modelView),
|
m_modelView1(modelView),
|
||||||
m_projectionMatrix(projectionMatrix),
|
m_projectionMatrix(projectionMatrix),
|
||||||
m_modelMat(modelMat)
|
m_modelMat(modelMat),
|
||||||
|
m_localScaling(localScaling)
|
||||||
{
|
{
|
||||||
|
|
||||||
}
|
}
|
||||||
@@ -46,9 +48,12 @@ struct Shader : public IShader {
|
|||||||
|
|
||||||
//varying_nrm.set_col(nthvert, proj<3>((m_projectionMatrix*m_modelView).invert_transpose()*embed<4>(m_model->normal(iface, nthvert), 0.f)));
|
//varying_nrm.set_col(nthvert, proj<3>((m_projectionMatrix*m_modelView).invert_transpose()*embed<4>(m_model->normal(iface, nthvert), 0.f)));
|
||||||
varying_nrm.set_col(nthvert, proj<3>((m_modelMat).invert_transpose()*embed<4>(m_model->normal(iface, nthvert), 0.f)));
|
varying_nrm.set_col(nthvert, proj<3>((m_modelMat).invert_transpose()*embed<4>(m_model->normal(iface, nthvert), 0.f)));
|
||||||
Vec4f gl_Vertex = m_projectionMatrix*m_modelView1*embed<4>(m_model->vert(iface, nthvert));
|
Vec3f unScaledVert = m_model->vert(iface, nthvert);
|
||||||
|
Vec3f scaledVert=Vec3f(unScaledVert[0]*m_localScaling[0],unScaledVert[1]*m_localScaling[1],unScaledVert[2]*m_localScaling[2]);
|
||||||
|
Vec4f gl_Vertex = m_projectionMatrix*m_modelView1*embed<4>(scaledVert);
|
||||||
|
|
||||||
varying_tri.set_col(nthvert, gl_Vertex);
|
varying_tri.set_col(nthvert, gl_Vertex);
|
||||||
ndc_tri.set_col(nthvert, proj<3>(gl_Vertex/gl_Vertex[3]));
|
//ndc_tri.set_col(nthvert, proj<3>(gl_Vertex/gl_Vertex[3]));
|
||||||
return gl_Vertex;
|
return gl_Vertex;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -56,25 +61,9 @@ struct Shader : public IShader {
|
|||||||
Vec3f bn = (varying_nrm*bar).normalize();
|
Vec3f bn = (varying_nrm*bar).normalize();
|
||||||
Vec2f uv = varying_uv*bar;
|
Vec2f uv = varying_uv*bar;
|
||||||
|
|
||||||
mat<3,3,float> A;
|
//float diff = 1;//full-bright
|
||||||
A[0] = ndc_tri.col(1) - ndc_tri.col(0);
|
float ambient = 0.7;
|
||||||
A[1] = ndc_tri.col(2) - ndc_tri.col(0);
|
float diff = ambient+b3Min(b3Max(0.f, bn*light_dir_world),(1-ambient));
|
||||||
A[2] = bn;
|
|
||||||
|
|
||||||
mat<3,3,float> AI = A.invert();
|
|
||||||
|
|
||||||
Vec3f i = AI * Vec3f(varying_uv[0][1] - varying_uv[0][0], varying_uv[0][2] - varying_uv[0][0], 0);
|
|
||||||
Vec3f j = AI * Vec3f(varying_uv[1][1] - varying_uv[1][0], varying_uv[1][2] - varying_uv[1][0], 0);
|
|
||||||
|
|
||||||
mat<3,3,float> B;
|
|
||||||
B.set_col(0, i.normalize());
|
|
||||||
B.set_col(1, j.normalize());
|
|
||||||
B.set_col(2, bn);
|
|
||||||
|
|
||||||
Vec3f n = (B*m_model->normal(uv)).normalize();
|
|
||||||
|
|
||||||
//float diff = 1;//b3Min(b3Max(0.f, n*0.3f),1.f);
|
|
||||||
float diff = b3Min(b3Max(0.f, bn*light_dir_world+0.3f),1.f);
|
|
||||||
//float diff = b3Max(0.f, n*m_light_dir_local);
|
//float diff = b3Max(0.f, n*m_light_dir_local);
|
||||||
color = m_model->diffuse(uv)*diff;
|
color = m_model->diffuse(uv)*diff;
|
||||||
|
|
||||||
@@ -95,7 +84,8 @@ m_userIndex(-1)
|
|||||||
Vec3f eye(1,1,3);
|
Vec3f eye(1,1,3);
|
||||||
Vec3f center(0,0,0);
|
Vec3f center(0,0,0);
|
||||||
Vec3f up(0,0,1);
|
Vec3f up(0,0,1);
|
||||||
|
m_lightDirWorld.setValue(0,0,0);
|
||||||
|
m_localScaling.setValue(1,1,1);
|
||||||
m_modelMatrix = Matrix::identity();
|
m_modelMatrix = Matrix::identity();
|
||||||
m_viewMatrix = lookat(eye, center, up);
|
m_viewMatrix = lookat(eye, center, up);
|
||||||
//m_viewportMatrix = viewport(width/8, height/8, width*3/4, height*3/4);
|
//m_viewportMatrix = viewport(width/8, height/8, width*3/4, height*3/4);
|
||||||
@@ -232,14 +222,12 @@ TinyRenderObjectData::~TinyRenderObjectData()
|
|||||||
|
|
||||||
void TinyRenderer::renderObject(TinyRenderObjectData& renderData)
|
void TinyRenderer::renderObject(TinyRenderObjectData& renderData)
|
||||||
{
|
{
|
||||||
|
light_dir_world = Vec3f(renderData.m_lightDirWorld[0],renderData.m_lightDirWorld[1],renderData.m_lightDirWorld[2]);
|
||||||
Model* model = renderData.m_model;
|
Model* model = renderData.m_model;
|
||||||
if (0==model)
|
if (0==model)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
Vec3f eye(renderData.m_eye[0],renderData.m_eye[1],renderData.m_eye[2]);
|
|
||||||
Vec3f center(renderData.m_center[0],renderData.m_center[1],renderData.m_center[2]);
|
|
||||||
Vec3f up(0,0,1);
|
|
||||||
|
|
||||||
|
|
||||||
//renderData.m_viewMatrix = lookat(eye, center, up);
|
//renderData.m_viewMatrix = lookat(eye, center, up);
|
||||||
int width = renderData.m_width;
|
int width = renderData.m_width;
|
||||||
@@ -258,9 +246,10 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData)
|
|||||||
|
|
||||||
{
|
{
|
||||||
Matrix modelViewMatrix = renderData.m_viewMatrix*renderData.m_modelMatrix;
|
Matrix modelViewMatrix = renderData.m_viewMatrix*renderData.m_modelMatrix;
|
||||||
|
Vec3f localScaling(renderData.m_localScaling[0],renderData.m_localScaling[1],renderData.m_localScaling[2]);
|
||||||
|
Shader shader(model, light_dir_local, modelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling);
|
||||||
|
|
||||||
Shader shader(model, light_dir_local, modelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix);
|
|
||||||
|
|
||||||
|
|
||||||
for (int i=0; i<model->nfaces(); i++) {
|
for (int i=0; i<model->nfaces(); i++) {
|
||||||
|
|
||||||
|
|||||||
@@ -16,9 +16,8 @@ struct TinyRenderObjectData
|
|||||||
Matrix m_viewMatrix;
|
Matrix m_viewMatrix;
|
||||||
Matrix m_projectionMatrix;
|
Matrix m_projectionMatrix;
|
||||||
Matrix m_viewportMatrix;
|
Matrix m_viewportMatrix;
|
||||||
|
btVector3 m_localScaling;
|
||||||
btVector3 m_eye;
|
btVector3 m_lightDirWorld;
|
||||||
btVector3 m_center;
|
|
||||||
|
|
||||||
//Model (vertices, indices, textures, shader)
|
//Model (vertices, indices, textures, shader)
|
||||||
Matrix m_modelMatrix;
|
Matrix m_modelMatrix;
|
||||||
|
|||||||
Reference in New Issue
Block a user