This commit is contained in:
erwin coumans
2016-05-19 09:19:44 -07:00
35 changed files with 8120 additions and 268 deletions

View File

@@ -15,10 +15,10 @@ struct DrawGridData
int upAxis;
float gridColor[4];
DrawGridData()
DrawGridData(int upAxis=1)
:gridSize(10),
upOffset(0.001f),
upAxis(1)
upAxis(upAxis)
{
gridColor[0] = 0.6f;
gridColor[1] = 0.6f;
@@ -119,6 +119,7 @@ struct CommonGraphicsApp
virtual void swapBuffer() = 0;
virtual void drawText( const char* txt, int posX, int posY) = 0;
virtual void drawText3D( const char* txt, float posX, float posZY, float posZ, float size)=0;
virtual void drawTexturedRect(float x0, float y0, float x1, float y1, float color[4], float u0,float v0, float u1, float v1, int useRGBA)=0;
virtual int registerCubeShape(float halfExtentsX,float halfExtentsY, float halfExtentsZ, int textureIndex = -1, float textureScaling = 1)=0;
virtual int registerGraphicsUnitSphereShape(EnumSphereLevelOfDetail lod, int textureId=-1) = 0;

View File

@@ -40,12 +40,14 @@ struct ButtonParams
const char* m_name;
int m_buttonId;
void* m_userPointer;
bool m_isTrigger;
ButtonParamChangedCallback m_callback;
ButtonParams(const char* name, int buttonId, bool isTrigger)
:m_name(name),
m_buttonId(buttonId),
m_userPointer(0),
m_isTrigger(isTrigger),
m_callback(0)
{
}

View File

@@ -64,7 +64,7 @@
#include "../ExtendedTutorials/SimpleCloth.h"
#include "../ExtendedTutorials/Chain.h"
#include "../ExtendedTutorials/Bridge.h"
#include "../ExtendedTutorials/RigidBodyFromObj.h"
#include "../ExtendedTutorials/RigidBodyFromObj.h"
struct ExampleEntry
{
@@ -89,38 +89,38 @@ struct ExampleEntry
static ExampleEntry gDefaultExamples[]=
{
ExampleEntry(0,"API"),
ExampleEntry(1,"Basic Example","Create some rigid bodies using box collision shapes. This is a good example to familiarize with the basic initialization of Bullet. The Basic Example can also be compiled without graphical user interface, as a console application. Press W for wireframe, A to show AABBs, I to suspend/restart physics simulation. Press D to toggle auto-deactivation of the simulation. ", BasicExampleCreateFunc),
ExampleEntry(1,"Rolling Friction", "Damping is often not good enough to keep rounded objects from rolling down a sloped surface. Instead, you can set the rolling friction of a rigid body. Generally it is best to leave the rolling friction to zero, to avoid artifacts.", RollingFrictionCreateFunc),
ExampleEntry(1,"Constraints","Show the use of the various constraints in Bullet. Press the L key to visualize the constraint limits. Press the C key to visualize the constraint frames.",
ExampleEntry(1,"Constraints","Show the use of the various constraints in Bullet. Press the L key to visualize the constraint limits. Press the C key to visualize the constraint frames.",
AllConstraintCreateFunc),
ExampleEntry(1,"Motorized Hinge","Use of a btHingeConstraint. You can adjust the first slider to change the target velocity, and the second slider to adjust the maximum impulse applied to reach the target velocity. Note that the hinge angle can reach beyond -360 and 360 degrees.", ConstraintCreateFunc),
ExampleEntry(1,"TestHingeTorque", "Apply a torque in the hinge axis. This example uses a btHingeConstraint and btRigidBody. The setup is similar to the multi body example TestJointTorque.",
TestHingeTorqueCreateFunc),
// ExampleEntry(0,"What's new in 2.83"),
ExampleEntry(1,"6DofSpring2","Show the use of the btGeneric6DofSpring2Constraint. This is a replacement of the btGeneric6DofSpringConstraint, it has various improvements. This includes improved spring implementation and better control over the restitution (bounce) when the constraint hits its limits.",
ExampleEntry(1,"6DofSpring2","Show the use of the btGeneric6DofSpring2Constraint. This is a replacement of the btGeneric6DofSpringConstraint, it has various improvements. This includes improved spring implementation and better control over the restitution (bounce) when the constraint hits its limits.",
Dof6Spring2CreateFunc),
ExampleEntry(1,"Motor Demo", "Dynamic control the target velocity of a motor of a btHingeConstraint. This demo makes use of the 'internal tick callback'. You can press W for wireframe, C and L to visualize constraint frame and limits.", MotorControlCreateFunc),
ExampleEntry(1,"Gyroscopic", "Show the Dzhanibekov effect using various settings of the gyroscopic term. You can select the gyroscopic term computation using btRigidBody::setFlags, with arguments BT_ENABLE_GYROSCOPIC_FORCE_EXPLICIT (using explicit integration, which adds energy and can lead to explosions), BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_WORLD, BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_BODY. If you don't set any of these flags, there is no gyroscopic term used.", GyroscopicCreateFunc),
ExampleEntry(1,"Soft Contact", "Using the error correction parameter (ERP) and constraint force mixing (CFM) values for contacts to simulate compliant contact.",RigidBodySoftContactCreateFunc),
ExampleEntry(0,"MultiBody"),
ExampleEntry(1,"MultiDofCreateFunc","Create a basic btMultiBody with 3-DOF spherical joints (mobilizers). The demo uses a fixed base or a floating base at restart.", MultiDofCreateFunc),
ExampleEntry(1,"TestJointTorque","Apply a torque to a btMultiBody with 1-DOF joints (mobilizers). This setup is similar to API/TestHingeTorque.", TestJointTorqueCreateFunc),
ExampleEntry(1,"TestPendulum","Simulate a pendulum using btMultiBody with a constant joint torque applied. The same code is also used as a unit test comparing Bullet with the numerical solution of second-order non-linear differential equation stored in pendulum_gold.h", TestPendulumCreateFunc),
ExampleEntry(1,"Constraint Feedback", "The example shows how to receive joint reaction forces in a btMultiBody. Also the applied impulse is available for a btMultiBodyJointMotor", MultiBodyConstraintFeedbackCreateFunc),
ExampleEntry(1,"Inverted Pendulum PD","Keep an inverted pendulum up using open loop PD control", InvertedPendulumPDControlCreateFunc),
ExampleEntry(1,"MultiBody Soft Contact", "Using the error correction parameter (ERP) and constraint force mixing (CFM) values for contacts to simulate compliant contact.",MultiBodySoftContactCreateFunc,0),
@@ -129,7 +129,7 @@ static ExampleEntry gDefaultExamples[]=
ExampleEntry(0,"Inverse Dynamics"),
ExampleEntry(1,"Inverse Dynamics URDF", "Create a btMultiBody from URDF. Create an inverse MultiBodyTree model from that. Use either decoupled PD control or computed torque control using the inverse model to track joint position targets", InverseDynamicsExampleCreateFunc,BT_ID_LOAD_URDF),
ExampleEntry(1,"Inverse Dynamics Prog", "Create a btMultiBody programatically. Create an inverse MultiBodyTree model from that. Use either decoupled PD control or computed torque control using the inverse model to track joint position targets", InverseDynamicsExampleCreateFunc,BT_ID_PROGRAMMATICALLY),
ExampleEntry(0,"Tutorial"),
ExampleEntry(1,"Constant Velocity","Free moving rigid body, without external or constraint forces", TutorialCreateFunc,TUT_VELOCITY),
ExampleEntry(1,"Gravity Acceleration","Motion of a free falling rigid body under constant gravitational acceleration", TutorialCreateFunc,TUT_ACCELERATION),
@@ -140,13 +140,13 @@ static ExampleEntry gDefaultExamples[]=
ExampleEntry(0,"Collision"),
ExampleEntry(1, "Spheres & Plane C-API (Bullet2)", "Collision C-API using Bullet 2.x backend", CollisionTutorialBullet2CreateFunc,TUT_SPHERE_PLANE_BULLET2),
//ExampleEntry(1, "Spheres & Plane C-API (Bullet3)", "Collision C-API using Bullet 3.x backend", CollisionTutorialBullet2CreateFunc,TUT_SPHERE_PLANE_RTB3),
#ifdef INCLUDE_CLOTH_DEMOS
ExampleEntry(0,"Soft Body"),
ExampleEntry(1,"Cloth","Simulate a patch of cloth.", SoftDemoCreateFunc,0),
ExampleEntry(1,"Pressure","Simulate 3d soft body using a pressure constraint.",SoftDemoCreateFunc,1),
ExampleEntry(1,"Volume","Simulate 3d soft body using a volume constraint.",SoftDemoCreateFunc,2),
ExampleEntry(1,"Ropes","Simulate ropes", SoftDemoCreateFunc,3),
@@ -154,7 +154,7 @@ static ExampleEntry gDefaultExamples[]=
ExampleEntry(1,"Cloth Attach","A rigid body attached to a cloth.", SoftDemoCreateFunc,5),
ExampleEntry(1,"Sticks","Show simulation of ropes fixed to the ground.", SoftDemoCreateFunc,6),
ExampleEntry(1,"Capsule Collision","Collision detection between a capsule shape and cloth.", SoftDemoCreateFunc,7),
ExampleEntry(1,"Collide","Soft body collision", SoftDemoCreateFunc,8),
ExampleEntry(1,"Collide 2","Soft body collision",SoftDemoCreateFunc,9),
ExampleEntry(1,"Collide 3","Soft body collision",SoftDemoCreateFunc,10),
@@ -180,7 +180,7 @@ static ExampleEntry gDefaultExamples[]=
ExampleEntry(1,"Cluster Stack Mixed","Stacking of soft bodies and rigid bodies.",SoftDemoCreateFunc,29),
ExampleEntry(1,"Tetra Cube","Simulate a volumetric soft body cube defined by tetrahedra.", SoftDemoCreateFunc,30),
ExampleEntry(1,"Tetra Bunny","Simulate a volumetric soft body Stanford bunny defined by tetrahedra.", SoftDemoCreateFunc,31),
#endif //INCLUDE_CLOTH_DEMOS
///we disable the benchmarks in debug mode, they are way too slow and benchmarking in debug mode is not recommended
@@ -197,7 +197,7 @@ static ExampleEntry gDefaultExamples[]=
#endif
ExampleEntry(0,"Importers"),
ExampleEntry(1,"Import .bullet", "Load a binary .bullet file. The serialization mechanism can deal with versioning, differences in endianess, 32 and 64bit, double/single precision. It is easy to save a .bullet file, see the examples/Importers/ImportBullet/SerializeDemo.cpp for a code example how to export a .bullet file.", SerializeBulletCreateFunc),
@@ -207,50 +207,56 @@ static ExampleEntry gDefaultExamples[]=
ExampleEntry(1,"Obj2RigidBody Optimize", "Load a triangle mesh from Wavefront .obj, remove the vertices that are not on the convex hull", ET_RigidBodyFromObjCreateFunc,OptimizeConvexObj),
ExampleEntry(1,"Quake BSP", "Import a Quake .bsp file", ImportBspCreateFunc, 0),
ExampleEntry(1,"COLLADA dae", "Import the geometric mesh data from a COLLADA file. This is used as part of the URDF importer. This loader can also be used to import collision geometry in general. ",
ExampleEntry(1,"COLLADA dae", "Import the geometric mesh data from a COLLADA file. This is used as part of the URDF importer. This loader can also be used to import collision geometry in general. ",
ImportColladaCreateFunc, 0),
ExampleEntry(1,"STL", "Import the geometric mesh data from a STL file. This is used as part of the URDF importer. This loader can also be used to import collision geometry in general. ",ImportSTLCreateFunc, 0),
ExampleEntry(1,"URDF (RigidBody)", "Import a URDF file, and create rigid bodies (btRigidBody) connected by constraints.", ImportURDFCreateFunc, 0),
ExampleEntry(1,"URDF (MultiBody)", "Import a URDF file and create a single multibody (btMultiBody) with tree hierarchy of links (mobilizers).",
ExampleEntry(1,"URDF (MultiBody)", "Import a URDF file and create a single multibody (btMultiBody) with tree hierarchy of links (mobilizers).",
ImportURDFCreateFunc, 1),
ExampleEntry(1,"SDF (MultiBody)", "Import an SDF file, create multiple multibodies etc", ImportSDFCreateFunc),
ExampleEntry(0,"Vehicles"),
ExampleEntry(1,"Hinge2 Vehicle", "A rigid body chassis with 4 rigid body wheels attached by a btHinge2Constraint",Hinge2VehicleCreateFunc),
ExampleEntry(1,"ForkLift","Simulate a fork lift vehicle with a working fork lift that can be moved using the cursor keys. The wheels collision is simplified using ray tests."
"There are currently some issues with the wheel rendering, the wheels rotate when picking up the object."
"The demo implementation allows to choose various MLCP constraint solvers.",
"The demo implementation allows to choose various MLCP constraint solvers.",
ForkLiftCreateFunc),
ExampleEntry(0,"Raycast"),
ExampleEntry(1,"Raytest", "Cast rays using the btCollisionWorld::rayTest method. The example shows how to receive the hit position and normal along the ray against the first object. Also it shows how to receive all the hits along a ray.", RaytestCreateFunc),
ExampleEntry(1,"Raytracer","Implement an extremely simple ray tracer using the ray trace functionality in btCollisionWorld.",
ExampleEntry(1,"Raytracer","Implement an extremely simple ray tracer using the ray trace functionality in btCollisionWorld.",
RayTracerCreateFunc),
ExampleEntry(0,"Experiments"),
ExampleEntry(1,"Robot Control", "Create a physics client and server to create and control robots.",
PhysicsClientCreateFunc, eCLIENTEXAMPLE_SERVER),
ExampleEntry(1,"Physics Server", "Create a physics server that communicates with a physics client over shared memory",
PhysicsServerCreateFunc),
ExampleEntry(1,"Physics Server (RTC)", "Create a physics server that communicates with a physics client over shared memory. At each update, the Physics Server will continue calling 'stepSimulation' based on the real-time clock (RTC).",
PhysicsServerCreateFunc,PHYSICS_SERVER_USE_RTC_CLOCK),
ExampleEntry(1,"Physics Server (Logging)", "Create a physics server that communicates with a physics client over shared memory. It will log all commands to a file.",
PhysicsServerCreateFunc,PHYSICS_SERVER_ENABLE_COMMAND_LOGGING),
ExampleEntry(1,"Physics Server (Replay Log)", "Create a physics server that replay a command log from disk.",
PhysicsServerCreateFunc,PHYSICS_SERVER_REPLAY_FROM_COMMAND_LOG),
ExampleEntry(1, "Physics Client", "Create a physics client that can communicate with a physics server over shared memory", PhysicsClientCreateFunc),
#ifdef ENABLE_LUA
ExampleEntry(1,"Lua Script", "Create the dynamics world, collision shapes and rigid bodies using Lua scripting",
LuaDemoCreateFunc),
#endif
ExampleEntry(1,"MultiThreading (submitJob)", "Simple example of executing jobs across multiple threads.",
MultiThreadingExampleCreateFunc,SINGLE_SIM_THREAD),
ExampleEntry(1,"Voronoi Fracture", "Automatically create a compound rigid body using voronoi tesselation. Individual parts are modeled as rigid bodies using a btConvexHullShape.",
VoronoiFractureCreateFunc),
ExampleEntry(1,"Fracture demo", "Create a basic custom implementation to model fracturing objects, based on a btCompoundShape. It explicitly propagates the collision impulses and breaks the rigid body into multiple rigid bodies. Press F to toggle fracture and glue mode.", FractureDemoCreateFunc),
ExampleEntry(1,"Planar 2D","Show the use of 2D collision shapes and rigid body simulation. The collision shape is wrapped into a btConvex2dShape. The rigid bodies are restricted in a plane using the 'setAngularFactor' and 'setLinearFactor' API call.",Planar2DCreateFunc),
@@ -260,7 +266,7 @@ static ExampleEntry gDefaultExamples[]=
ExampleEntry(1,"CoordinateSystemDemo","Show the axis and positive rotation direction around the axis.", CoordinateSystemCreateFunc),
ExampleEntry(1,"Time Series", "Render some value(s) in a 2D graph window, shifting to the left", TimeSeriesCreateFunc),
ExampleEntry(1,"TinyRenderer", "Very small software renderer.", TinyRendererCreateFunc),
//Extended Tutorials Added by Mobeen
ExampleEntry(0,"Extended Tutorials"),
ExampleEntry(1,"Simple Box", "Simplest possible demo creating a single box rigid body that falls under gravity", ET_SimpleBoxCreateFunc),
@@ -269,7 +275,7 @@ static ExampleEntry gDefaultExamples[]=
ExampleEntry(1,"Simple Cloth", "Creating a simple piece of cloth", ET_SimpleClothCreateFunc),
ExampleEntry(1,"Simple Chain", "Creating a simple chain using a pair of point2point/distance constraints. You may click and drag any box to see the chain respond.", ET_ChainCreateFunc),
ExampleEntry(1,"Simple Bridge", "Creating a simple bridge using a pair of point2point/distance constraints. You may click and drag any plank to see the bridge respond.", ET_BridgeCreateFunc),
//todo: create a category/tutorial about advanced topics, such as optimizations, using different collision detection algorithm, different constraint solvers etc.
//ExampleEntry(0,"Advanced"),
//ExampleEntry(1,"Obj2RigidBody Add Features", "Load a triangle mesh from Wavefront .obj and create polyhedral features to perform the separating axis test (instead of GJK/MPR). It is best to combine optimization and polyhedral feature generation.", ET_RigidBodyFromObjCreateFunc,OptimizeConvexObj+ComputePolyhedralFeatures),
@@ -328,8 +334,8 @@ void ExampleEntriesAll::initExampleEntries()
{
m_data->m_allExamples.push_back(gAdditionalRegisteredExamples[i]);
}
int numDefaultEntries = sizeof(gDefaultExamples)/sizeof(ExampleEntry);
for (int i=0;i<numDefaultEntries;i++)

View File

@@ -141,7 +141,8 @@ void GwenParameterInterface::registerButtonParameter(ButtonParams& params)
MyButtonEventHandler* handler = new MyButtonEventHandler(params.m_callback,params.m_buttonId,params.m_userPointer);
button->SetText(params.m_name);
button->onPress.Add( handler, &MyButtonEventHandler::onButtonPress );
button->SetIsToggle(params.m_isTrigger);
m_paramInternalData->m_buttons.push_back(button);
m_paramInternalData->m_buttonEventHandlers.push_back(handler);
@@ -190,8 +191,8 @@ void GwenParameterInterface::registerComboBox(ComboBoxParams& params)
combobox->onSelection.Add(handler,&MyComboBoxHander2::onSelect);
int ypos = m_gwenInternalData->m_curYposition;
m_gwenInternalData->m_curYposition+=22;
combobox->SetPos(10, ypos );
combobox->SetWidth( 100 );
combobox->SetPos(5, ypos );
combobox->SetWidth( 220 );
//box->SetPos(120,130);
for (int i=0;i<params.m_numItems;i++)
{
@@ -200,6 +201,7 @@ void GwenParameterInterface::registerComboBox(ComboBoxParams& params)
combobox->OnItemSelected(item);
}
}

View File

@@ -76,17 +76,17 @@ public:
virtual ~ExampleEntriesPhysicsServer();
static void registerExampleEntry(int menuLevel, const char* name,const char* description, CommonExampleInterface::CreateFunc* createFunc, int option=0);
virtual void initExampleEntries();
virtual void initOpenCLExampleEntries();
virtual int getNumRegisteredExamples();
virtual CommonExampleInterface::CreateFunc* getExampleCreateFunc(int index);
virtual const char* getExampleName(int index);
virtual const char* getExampleDescription(int index);
virtual int getExampleOption(int index);
@@ -120,11 +120,14 @@ struct ExampleEntriesInternalData2
static ExampleEntryPhysicsServer gDefaultExamplesPhysicsServer[]=
{
ExampleEntryPhysicsServer(0,"Robotics Control"),
ExampleEntryPhysicsServer(1,"Physics Server", "Create a physics server that communicates with a physics client over shared memory",
PhysicsServerCreateFunc),
ExampleEntryPhysicsServer(1,"Physics Server (RTC)", "Create a physics server that communicates with a physics client over shared memory. At each update, the Physics Server will continue calling 'stepSimulation' based on the real-time clock (RTC).",
PhysicsServerCreateFunc,PHYSICS_SERVER_USE_RTC_CLOCK),
ExampleEntryPhysicsServer(1,"Physics Server (Logging)", "Create a physics server that communicates with a physics client over shared memory. It will log all commands to a file.",
PhysicsServerCreateFunc,PHYSICS_SERVER_ENABLE_COMMAND_LOGGING),
ExampleEntryPhysicsServer(1,"Physics Server (Replay Log)", "Create a physics server that replay a command log from disk.",
@@ -152,7 +155,7 @@ void ExampleEntriesPhysicsServer::initExampleEntries()
{
m_data->m_allExamples.clear();
int numDefaultEntries = sizeof(gDefaultExamplesPhysicsServer)/sizeof(ExampleEntryPhysicsServer);
for (int i=0;i<numDefaultEntries;i++)
@@ -231,8 +234,8 @@ void ExampleBrowserThreadFunc(void* userPtr,void* lsMemory)
int workLeft = true;
b3CommandLineArgs args2(args->m_argc,args->m_argv);
b3Clock clock;
ExampleEntriesPhysicsServer examples;
examples.initExampleEntries();
@@ -243,12 +246,12 @@ void ExampleBrowserThreadFunc(void* userPtr,void* lsMemory)
clock.reset();
if (init)
{
args->m_cs->lock();
args->m_cs->setSharedParam(0,eExampleBrowserIsInitialized);
args->m_cs->unlock();
do
do
{
float deltaTimeInSeconds = clock.getTimeMicroseconds()/1000000.f;
clock.reset();
@@ -405,7 +408,7 @@ void btUpdateInProcessExampleBrowserMainThread(btInProcessExampleBrowserMainThre
}
void btShutDownExampleBrowserMainThread(btInProcessExampleBrowserMainThreadInternalData* data)
{
data->m_exampleBrowser->setSharedMemoryInterface(0);
delete data->m_exampleBrowser;
delete data;

View File

@@ -12,32 +12,28 @@
#include "stb_image/stb_image.h"
int b3ImportMeshUtility::loadAndRegisterMeshFromFile(const std::string& fileName, CommonRenderInterface* renderer)
bool b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(const std::string& fileName, b3ImportMeshData& meshData)
{
int shapeId = -1;
char relativeFileName[1024];
meshData.m_gfxShape = 0;
meshData.m_textureImage = 0;
meshData.m_textureHeight = 0;
meshData.m_textureWidth = 0;
char relativeFileName[1024];
if (b3ResourcePath::findResourcePath(fileName.c_str(), relativeFileName, 1024))
{
char pathPrefix[1024];
b3FileUtils::extractPath(relativeFileName, pathPrefix, 1024);
btVector3 shift(0,0,0);
// int index=10;
{
btVector3 shift(0,0,0);
std::vector<tinyobj::shape_t> shapes;
std::string err = tinyobj::LoadObj(shapes, relativeFileName, pathPrefix);
GLInstanceGraphicsShape* gfxShape = btgCreateGraphicsShapeFromWavefrontObj(shapes);
int textureIndex = -1;
//try to load some texture
for (int i=0;i<shapes.size();i++)
@@ -48,7 +44,7 @@ int b3ImportMeshUtility::loadAndRegisterMeshFromFile(const std::string& fileName
int width,height,n;
const char* filename = shape.material.diffuse_texname.c_str();
const unsigned char* image=0;
unsigned char* image=0;
const char* prefix[]={ pathPrefix,"./","./data/","../data/","../../data/","../../../data/","../../../../data/"};
int numprefix = sizeof(prefix)/sizeof(const char*);
@@ -61,37 +57,59 @@ int b3ImportMeshUtility::loadAndRegisterMeshFromFile(const std::string& fileName
if (b3ResourcePath::findResourcePath(relativeFileName, relativeFileName2, 1024))
{
image = stbi_load(relativeFileName, &width, &height, &n, 3);
meshData.m_textureImage = image;
if (image)
{
meshData.m_textureWidth = width;
meshData.m_textureHeight = height;
} else
{
meshData.m_textureWidth = 0;
meshData.m_textureHeight = 0;
}
} else
{
b3Warning("not found %s\n",relativeFileName);
}
}
if (image)
{
textureIndex = renderer->registerTexture(image,width,height);
if (textureIndex>=0)
{
break;
}
}
}
}
shapeId = renderer->registerShape(&gfxShape->m_vertices->at(0).xyzw[0], gfxShape->m_numvertices, &gfxShape->m_indices->at(0), gfxShape->m_numIndices,B3_GL_TRIANGLES,textureIndex);
meshData.m_gfxShape = gfxShape;
return true;
}
}
else
{
b3Warning("Cannot find %s\n", fileName.c_str());
}
return shapeId;
return false;
}
int b3ImportMeshUtility::loadAndRegisterMeshFromFile(const std::string& fileName, CommonRenderInterface* renderer)
{
int shapeId = -1;
b3ImportMeshData meshData;
if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(fileName, meshData))
{
int textureIndex = 0;
if (meshData.m_textureImage)
{
textureIndex = renderer->registerTexture(meshData.m_textureImage,meshData.m_textureWidth,meshData.m_textureHeight);
}
shapeId = renderer->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,
textureIndex);
delete meshData.m_gfxShape;
delete meshData.m_textureImage;
}
return shapeId;
}

View File

@@ -3,11 +3,22 @@
#include <string>
struct b3ImportMeshData
{
struct GLInstanceGraphicsShape* m_gfxShape;
unsigned char* m_textureImage;//in 3 component 8-bit RGB data
int m_textureWidth;
int m_textureHeight;
};
class b3ImportMeshUtility
{
public:
static int loadAndRegisterMeshFromFile(const std::string& fileName, class CommonRenderInterface* renderer);
static bool loadAndRegisterMeshFromFileInternal(const std::string& fileName, b3ImportMeshData& meshData);
};

View File

@@ -186,6 +186,7 @@ public:
{
return m_sdfModels.size();
}
return 0;
}
void activateModel(int modelIndex);

View File

@@ -18,6 +18,7 @@ public:
virtual void swapBuffer();
virtual void drawText( const char* txt, int posX, int posY);
virtual void drawTexturedRect(float x0, float y0, float x1, float y1, float color[4], float u0,float v0, float u1, float v1, int useRGBA){};
virtual void setBackgroundColor(float red, float green, float blue);
virtual int registerCubeShape(float halfExtentsX,float halfExtentsY, float halfExtentsZ, int textureIndex = -1, float textureScaling = 1)
{

View File

@@ -425,6 +425,18 @@ void SimpleOpenGL3App::drawText( const char* txt, int posXi, int posYi)
glDisable(GL_BLEND);
}
void SimpleOpenGL3App::drawTexturedRect(float x0, float y0, float x1, float y1, float color[4], float u0,float v0, float u1, float v1, int useRGBA)
{
glEnable(GL_BLEND);
glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
m_primRenderer->drawTexturedRect(x0,y0,x1,y1,color,u0,v0,u1,v1,useRGBA);
glDisable(GL_BLEND);
}
struct GfxVertex
{
float x,y,z,w;

View File

@@ -32,6 +32,7 @@ struct SimpleOpenGL3App : public CommonGraphicsApp
virtual void swapBuffer();
virtual void drawText( const char* txt, int posX, int posY);
virtual void drawText3D( const char* txt, float posX, float posZY, float posZ, float size);
virtual void drawTexturedRect(float x0, float y0, float x1, float y1, float color[4], float u0,float v0, float u1, float v1, int useRGBA);
struct sth_stash* getFontStash();

View File

@@ -6,25 +6,26 @@
#include "Bullet3Common/b3AlignedObjectArray.h"
#include "../CommonInterfaces/CommonRenderInterface.h"
#include "../TinyRenderer/TinyRenderer.h"
#include "../CommonInterfaces/Common2dCanvasInterface.h"
//#include "BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h"
#include "BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h"
//#include "BulletCollision/NarrowPhaseCollision/btGjkConvexCast.h"
//#include "BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.h"
#include "../CommonInterfaces/CommonExampleInterface.h"
#include "LinearMath/btAlignedObjectArray.h"
#include "btBulletCollisionCommon.h"
#include "../CommonInterfaces/CommonGUIHelperInterface.h"
#include "../ExampleBrowser/CollisionShape2TriangleMesh.h"
#include "../Importers/ImportMeshUtility/b3ImportMeshUtility.h"
#include "../OpenGLWindow/GLInstanceGraphicsShape.h"
#include "../CommonInterfaces/CommonParameterInterface.h"
struct TinyRendererSetup : public CommonExampleInterface
{
struct GUIHelperInterface* m_guiHelper;
struct CommonGraphicsApp* m_app;
struct TinyRendererSetupInternalData* m_internalData;
bool m_useSoftware;
TinyRendererSetup(struct CommonGraphicsApp* app);
TinyRendererSetup(struct GUIHelperInterface* guiHelper);
virtual ~TinyRendererSetup();
@@ -48,12 +49,16 @@ struct TinyRendererSetup : public CommonExampleInterface
virtual void renderScene()
{
}
void selectRenderer(int rendererIndex)
{
m_useSoftware = (rendererIndex==0);
}
};
struct TinyRendererSetupInternalData
{
int m_canvasIndex;
struct Common2dCanvasInterface* m_canvas;
TGAImage m_rgbColorBuffer;
b3AlignedObjectArray<float> m_depthBuffer;
@@ -70,43 +75,21 @@ struct TinyRendererSetupInternalData
btScalar m_roll;
btScalar m_yaw;
int m_textureHandle;
TinyRendererSetupInternalData(int width, int height)
:m_canvasIndex(-1),
m_canvas(0),
m_roll(0),
:m_roll(0),
m_pitch(0),
m_yaw(0),
m_width(width),
m_height(height),
m_rgbColorBuffer(width,height,TGAImage::RGB)
m_rgbColorBuffer(width,height,TGAImage::RGB),
m_textureHandle(0)
{
btConeShape* cone = new btConeShape(1,1);
btSphereShape* sphere = new btSphereShape(1);
btBoxShape* box = new btBoxShape (btVector3(1,1,1));
m_shapePtr.push_back(cone);
m_shapePtr.push_back(sphere);
m_shapePtr.push_back(box);
m_depthBuffer.resize(m_width*m_height);
for (int i=0;i<m_shapePtr.size();i++)
{
TinyRenderObjectData* ob = new TinyRenderObjectData(m_width,m_height,m_rgbColorBuffer,m_depthBuffer);
btAlignedObjectArray<btVector3> vertexPositions;
btAlignedObjectArray<btVector3> vertexNormals;
btAlignedObjectArray<int> indicesOut;
btTransform ident;
ident.setIdentity();
CollisionShape2TriangleMesh(m_shapePtr[i],ident,vertexPositions,vertexNormals,indicesOut);
m_renderObjects.push_back(ob);
ob->registerMesh2(vertexPositions,vertexNormals,indicesOut);
}
//ob->registerMeshShape(
updateTransforms();
}
}
void updateTransforms()
{
int numObjects = m_shapePtr.size();
@@ -114,7 +97,8 @@ struct TinyRendererSetupInternalData
for (int i=0;i<numObjects;i++)
{
m_transforms[i].setIdentity();
btVector3 pos(0.f,-(2.5* numObjects * 0.5)+i*2.5f, 0.f);
//btVector3 pos(0.f,-(2.5* numObjects * 0.5)+i*2.5f, 0.f);
btVector3 pos(0.f,+i*2.5f, 0.f);
m_transforms[i].setIdentity();
m_transforms[i].setOrigin( pos );
btQuaternion orn;
@@ -130,122 +114,197 @@ struct TinyRendererSetupInternalData
};
TinyRendererSetup::TinyRendererSetup(struct CommonGraphicsApp* app)
TinyRendererSetup::TinyRendererSetup(struct GUIHelperInterface* gui)
{
m_app = app;
m_internalData = new TinyRendererSetupInternalData(128,128);
m_useSoftware = false;
m_guiHelper = gui;
m_app = gui->getAppInterface();
m_internalData = new TinyRendererSetupInternalData(gui->getAppInterface()->m_window->getWidth(),gui->getAppInterface()->m_window->getHeight());
m_app->m_renderer->enableBlend(true);
const char* fileName = "textured_sphere_smooth.obj";//cube.obj";
{
{
int shapeId = -1;
b3ImportMeshData meshData;
if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(fileName, meshData))
{
int textureIndex = -1;
if (meshData.m_textureImage)
{
textureIndex = m_guiHelper->getRenderInterface()->registerTexture(meshData.m_textureImage,meshData.m_textureWidth,meshData.m_textureHeight);
}
shapeId = m_guiHelper->getRenderInterface()->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,
textureIndex);
float position[4]={0,0,0,1};
float orn[4]={0,0,0,1};
float color[4]={1,1,1,1};
float scaling[4]={1,1,1,1};
m_guiHelper->getRenderInterface()->registerGraphicsInstance(shapeId,position,orn,color,scaling);
m_guiHelper->getRenderInterface()->writeTransforms();
m_internalData->m_shapePtr.push_back(0);
TinyRenderObjectData* ob = new TinyRenderObjectData(m_internalData->m_width,m_internalData->m_height,
m_internalData->m_rgbColorBuffer,
m_internalData->m_depthBuffer);
//ob->loadModel("cube.obj");
const int* indices = &meshData.m_gfxShape->m_indices->at(0);
ob->registerMeshShape(&meshData.m_gfxShape->m_vertices->at(0).xyzw[0],
meshData.m_gfxShape->m_numvertices,
indices,
meshData.m_gfxShape->m_numIndices, meshData.m_textureImage,meshData.m_textureWidth,meshData.m_textureHeight);
m_internalData->m_renderObjects.push_back(ob);
delete meshData.m_gfxShape;
delete meshData.m_textureImage;
}
}
}
}
TinyRendererSetup::~TinyRendererSetup()
{
m_app->m_renderer->enableBlend(false);
delete m_internalData;
}
const char* items[] = {"Software", "OpenGL"};
void TinyRendererComboCallback(int combobox, const char* item, void* userPointer)
{
TinyRendererSetup* cl = (TinyRendererSetup*) userPointer;
b3Assert(cl);
int index=-1;
int numItems = sizeof(items)/sizeof(char*);
for (int i=0;i<numItems;i++)
{
if (!strcmp(item,items[i]))
{
index = i;
}
}
cl->selectRenderer(index);
}
void TinyRendererSetup::initPhysics()
{
//request a visual bitma/texture we can render to
m_app->setUpAxis(2);
m_internalData->m_canvas = m_app->m_2dCanvasInterface;
CommonRenderInterface* render = m_app->m_renderer;
if (m_internalData->m_canvas)
{
m_internalData->m_canvasIndex = m_internalData->m_canvas->createCanvas("tinyrenderer",m_internalData->m_width,m_internalData->m_height);
for (int i=0;i<m_internalData->m_width;i++)
{
for (int j=0;j<m_internalData->m_height;j++)
{
unsigned char red=255;
unsigned char green=255;
unsigned char blue=255;
unsigned char alpha=255;
m_internalData->m_canvas->setPixel(m_internalData->m_canvasIndex,i,j,red,green,blue,alpha);
}
}
m_internalData->m_canvas->refreshImageData(m_internalData->m_canvasIndex);
//int bitmapId = gfxBridge.createRenderBitmap(width,height);
}
m_internalData->m_textureHandle = render->registerTexture(m_internalData->m_rgbColorBuffer.buffer(),m_internalData->m_width,m_internalData->m_height);
ComboBoxParams comboParams;
comboParams.m_userPointer = this;
comboParams.m_numItems=sizeof(items)/sizeof(char*);
comboParams.m_startItem = 1;
comboParams.m_items=items;
comboParams.m_callback =TinyRendererComboCallback;
m_guiHelper->getParameterInterface()->registerComboBox( comboParams);
}
void TinyRendererSetup::exitPhysics()
{
if (m_internalData->m_canvas && m_internalData->m_canvasIndex>=0)
{
m_internalData->m_canvas->destroyCanvas(m_internalData->m_canvasIndex);
}
}
void TinyRendererSetup::stepSimulation(float deltaTime)
{
m_internalData->updateTransforms();
TGAColor clearColor;
clearColor.bgra[0] = 255;
clearColor.bgra[1] = 255;
clearColor.bgra[2] = 255;
clearColor.bgra[3] = 255;
for(int y=0;y<m_internalData->m_height;++y)
{
for(int x=0;x<m_internalData->m_width;++x)
{
m_internalData->m_rgbColorBuffer.set(x,y,clearColor);
m_internalData->m_depthBuffer[x+y*m_internalData->m_width] = -1e30f;
}
}
m_internalData->updateTransforms();
if (!m_useSoftware)
{
for (int i=0;i<m_internalData->m_transforms.size();i++)
{
m_guiHelper->getRenderInterface()->writeSingleInstanceTransformToCPU(m_internalData->m_transforms[i].getOrigin(),m_internalData->m_transforms[i].getRotation(),i);
}
m_guiHelper->getRenderInterface()->writeTransforms();
m_guiHelper->getRenderInterface()->renderScene();
} else
{
TGAColor clearColor;
clearColor.bgra[0] = 200;
clearColor.bgra[1] = 200;
clearColor.bgra[2] = 200;
clearColor.bgra[3] = 255;
for(int y=0;y<m_internalData->m_height;++y)
{
for(int x=0;x<m_internalData->m_width;++x)
{
m_internalData->m_rgbColorBuffer.set(x,y,clearColor);
m_internalData->m_depthBuffer[x+y*m_internalData->m_width] = -1e30f;
}
}
ATTRIBUTE_ALIGNED16(btScalar modelMat2[16]);
ATTRIBUTE_ALIGNED16(float viewMat[16]);
CommonRenderInterface* render = this->m_app->m_renderer;
render->getActiveCamera()->getCameraViewMatrix(viewMat);
ATTRIBUTE_ALIGNED16(btScalar modelMat2[16]);
ATTRIBUTE_ALIGNED16(float viewMat[16]);
ATTRIBUTE_ALIGNED16(float projMat[16]);
CommonRenderInterface* render = this->m_app->m_renderer;
render->getActiveCamera()->getCameraViewMatrix(viewMat);
render->getActiveCamera()->getCameraProjectionMatrix(projMat);
for (int o=0;o<this->m_internalData->m_renderObjects.size();o++)
{
const btTransform& tr = m_internalData->m_transforms[o];
tr.getOpenGLMatrix(modelMat2);
for (int i=0;i<4;i++)
{
for (int j=0;j<4;j++)
{
m_internalData->m_renderObjects[o]->m_modelMatrix[i][j] = float(modelMat2[i+4*j]);
m_internalData->m_renderObjects[o]->m_viewMatrix[i][j] = viewMat[i+4*j];
}
}
TinyRenderer::renderObject(*m_internalData->m_renderObjects[o]);
}
for (int o=0;o<this->m_internalData->m_renderObjects.size();o++)
{
const btTransform& tr = m_internalData->m_transforms[o];
tr.getOpenGLMatrix(modelMat2);
for (int i=0;i<4;i++)
{
for (int j=0;j<4;j++)
{
m_internalData->m_renderObjects[o]->m_modelMatrix[i][j] = float(modelMat2[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];
float eye[4];
float center[4];
render->getActiveCamera()->getCameraPosition(eye);
render->getActiveCamera()->getCameraTargetPosition(center);
for(int y=0;y<m_internalData->m_height;++y)
{
for(int x=0;x<m_internalData->m_width;++x)
{
const TGAColor& color = m_internalData->m_rgbColorBuffer.get(x,y);
m_internalData->m_canvas->setPixel(m_internalData->m_canvasIndex,x,(m_internalData->m_height-1-y),
color.bgra[2],color.bgra[1],color.bgra[0],255);
}
}
//m_internalData->m_canvas->setPixel(m_internalData->m_canvasIndex,x,y,255,0,0,255);
m_internalData->m_canvas->refreshImageData(m_internalData->m_canvasIndex);
m_internalData->m_renderObjects[o]->m_eye.setValue(eye[0],eye[1],eye[2]);
m_internalData->m_renderObjects[o]->m_center.setValue(center[0],center[1],center[2]);
}
}
TinyRenderer::renderObject(*m_internalData->m_renderObjects[o]);
}
//m_app->drawText("hello",500,500);
render->activateTexture(m_internalData->m_textureHandle);
render->updateTexture(m_internalData->m_textureHandle,m_internalData->m_rgbColorBuffer.buffer());
float color[4] = {1,1,1,1};
m_app->drawTexturedRect(0,0,m_app->m_window->getWidth(), m_app->m_window->getHeight(),color,0,0,1,1,true);
}
}
@@ -275,5 +334,5 @@ void TinyRendererSetup::syncPhysicsToGraphics(GraphicsPhysicsBridge& gfxBridge)
CommonExampleInterface* TinyRendererCreateFunc(struct CommonExampleOptions& options)
{
return new TinyRendererSetup(options.m_guiHelper->getAppInterface());
return new TinyRendererSetup(options.m_guiHelper);
}

View File

@@ -676,3 +676,34 @@ void b3GetDebugLines(b3PhysicsClientHandle physClient, struct b3DebugLines* l
}
}
///request an image from a simulated camera, using a software renderer.
b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physClient)
{
PhysicsClient* cl = (PhysicsClient* ) physClient;
b3Assert(cl);
b3Assert(cl->canSubmitCommand());
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command);
command->m_type =CMD_REQUEST_CAMERA_IMAGE_DATA;
return (b3SharedMemoryCommandHandle) command;
}
void b3RequestCameraImageSetResolution(b3SharedMemoryCommandHandle command, int pixelWidth, int pixelHeight)
{
}
void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle command, float viewMatrix[16], float projectionMatrix[16])
{
}
void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData)
{
PhysicsClient* cl = (PhysicsClient* ) physClient;
if (cl)
{
}
}

View File

@@ -64,7 +64,13 @@ b3SharedMemoryCommandHandle b3InitRequestDebugLinesCommand(b3PhysicsClientHandle
///Get the pointers to the debug line information, after b3InitRequestDebugLinesCommand returns
///status CMD_DEBUG_LINES_COMPLETED
void b3GetDebugLines(b3PhysicsClientHandle physClient, struct b3DebugLines* lines);
///request an image from a simulated camera, using a software renderer.
b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physClient);
void b3RequestCameraImageSetResolution(b3SharedMemoryCommandHandle command, int pixelWidth, int pixelHeight);
void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle command, float viewMatrix[16], float projectionMatrix[16]);
void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData);
b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient);
int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, double gravx,double gravy, double gravz);

View File

@@ -11,7 +11,7 @@
#include "PhysicsLoopBackC_API.h"
#include "PhysicsDirectC_API.h"
#include "PhysicsClientC_API.h"
#include "PhysicsServerSharedMemory.h"
struct MyMotorInfo2
{
btScalar m_velTarget;
@@ -28,6 +28,9 @@ class PhysicsClientExample : public SharedMemoryCommon
{
protected:
b3PhysicsClientHandle m_physicsClientHandle;
//this m_physicsServer is only used when option eCLIENTEXAMPLE_SERVER is enabled
PhysicsServerSharedMemory m_physicsServer;
bool m_wantsTermination;
btAlignedObjectArray<int> m_userCommandRequests;
@@ -38,15 +41,18 @@ protected:
void createButtons();
public:
//@todo, add accessor methods
// MyMotorInfo2 m_motorTargetVelocities[MAX_NUM_MOTORS];
MyMotorInfo2 m_motorTargetPositions[MAX_NUM_MOTORS];
int m_numMotors;
int m_options;
bool m_isOptionalServerConnected;
PhysicsClientExample(GUIHelperInterface* helper);
public:
PhysicsClientExample(GUIHelperInterface* helper, int options);
virtual ~PhysicsClientExample();
virtual void initPhysics();
@@ -93,6 +99,11 @@ public:
virtual void exitPhysics(){};
virtual void renderScene()
{
if (m_options == eCLIENTEXAMPLE_SERVER)
{
m_physicsServer.renderScene();
}
b3DebugLines debugLines;
b3GetDebugLines(m_physicsClientHandle,&debugLines);
int numLines = debugLines.m_numDebugLines;
@@ -153,7 +164,13 @@ public:
b3JointControlSetMaximumForce(commandHandle,uIndex,1000);
}
}
virtual void physicsDebugDraw(int debugFlags){}
virtual void physicsDebugDraw(int debugFlags)
{
if (m_options==eCLIENTEXAMPLE_SERVER)
{
m_physicsServer.physicsDebugDraw(debugFlags);
}
}
virtual bool mouseMoveCallback(float x,float y){return false;};
virtual bool mouseButtonCallback(int button, int state, float x, float y){return false;}
virtual bool keyboardCallback(int key, int state){return false;}
@@ -352,7 +369,7 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
case CMD_SEND_PHYSICS_SIMULATION_PARAMETERS: {
b3SharedMemoryCommandHandle commandHandle = b3InitPhysicsParamCommand(m_physicsClientHandle);
b3PhysicsParamSetGravity(commandHandle, 0.0, 0.0, -9.8);
b3SubmitClientCommandAndWaitStatus(m_physicsClientHandle, commandHandle);
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
break;
}
default:
@@ -365,14 +382,16 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
PhysicsClientExample::PhysicsClientExample(GUIHelperInterface* helper)
PhysicsClientExample::PhysicsClientExample(GUIHelperInterface* helper, int options)
:SharedMemoryCommon(helper),
m_physicsClientHandle(0),
m_wantsTermination(false),
m_sharedMemoryKey(SHARED_MEMORY_KEY),
m_selectedBody(-1),
m_prevSelectedBody(-1),
m_numMotors(0)
m_numMotors(0),
m_options(options),
m_isOptionalServerConnected(false)
{
b3Printf("Started PhysicsClientExample\n");
}
@@ -384,6 +403,12 @@ PhysicsClientExample::~PhysicsClientExample()
b3ProcessServerStatus(m_physicsClientHandle);
b3DisconnectSharedMemory(m_physicsClientHandle);
}
if (m_options == eCLIENTEXAMPLE_SERVER)
{
bool deInitializeSharedMemory = true;
m_physicsServer.disconnectSharedMemory(deInitializeSharedMemory);
}
b3Printf("~PhysicsClientExample\n");
}
@@ -406,7 +431,10 @@ void PhysicsClientExample::createButtons()
createButton("Load URDF",CMD_LOAD_URDF, isTrigger);
createButton("Step Sim",CMD_STEP_FORWARD_SIMULATION, isTrigger);
createButton("Send Bullet Stream",CMD_SEND_BULLET_DATA_STREAM, isTrigger);
createButton("Get State",CMD_REQUEST_ACTUAL_STATE, isTrigger);
if (m_options!=eCLIENTEXAMPLE_SERVER)
{
createButton("Get State",CMD_REQUEST_ACTUAL_STATE, isTrigger);
}
createButton("Send Desired State",CMD_SEND_DESIRED_STATE, isTrigger);
createButton("Create Box Collider",CMD_CREATE_BOX_COLLISION_SHAPE,isTrigger);
createButton("Create Cylinder Body",CMD_CREATE_RIGID_BODY,isTrigger);
@@ -477,6 +505,11 @@ void PhysicsClientExample::initPhysics()
m_selectedBody = -1;
m_prevSelectedBody = -1;
if (m_options == eCLIENTEXAMPLE_SERVER)
{
m_isOptionalServerConnected = m_physicsServer.connectSharedMemory( m_guiHelper);
}
m_physicsClientHandle = b3ConnectSharedMemory(m_sharedMemoryKey);
//m_physicsClientHandle = b3ConnectPhysicsLoopback(SHARED_MEMORY_KEY);
//m_physicsClientHandle = b3ConnectPhysicsDirect();
@@ -491,6 +524,15 @@ void PhysicsClientExample::initPhysics()
void PhysicsClientExample::stepSimulation(float deltaTime)
{
if (m_options == eCLIENTEXAMPLE_SERVER)
{
for (int i=0;i<100;i++)
{
m_physicsServer.processClientCommands();
}
}
if (m_prevSelectedBody != m_selectedBody)
{
createButtons();
@@ -564,10 +606,29 @@ void PhysicsClientExample::stepSimulation(float deltaTime)
m_selectedBody = -1;
m_numMotors=0;
createButtons();
}
prepareAndSubmitCommand(commandId);
b3SharedMemoryCommandHandle commandHandle = b3InitResetSimulationCommand(m_physicsClientHandle);
if (m_options == eCLIENTEXAMPLE_SERVER)
{
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
while (!b3CanSubmitCommand(m_physicsClientHandle))
{
m_physicsServer.processClientCommands();
b3SharedMemoryStatusHandle status = b3ProcessServerStatus(m_physicsClientHandle);
bool hasStatus = (status != 0);
if (hasStatus)
{
int statusType = b3GetStatusType(status);
b3Printf("Status after reset: %d",statusType);
}
}
} else
{
prepareAndSubmitCommand(commandId);
}
} else
{
prepareAndSubmitCommand(commandId);
}
} else
{
@@ -575,7 +636,10 @@ void PhysicsClientExample::stepSimulation(float deltaTime)
{
enqueueCommand(CMD_SEND_DESIRED_STATE);
enqueueCommand(CMD_STEP_FORWARD_SIMULATION);
enqueueCommand(CMD_REQUEST_DEBUG_LINES);
if (m_options != eCLIENTEXAMPLE_SERVER)
{
enqueueCommand(CMD_REQUEST_DEBUG_LINES);
}
//enqueueCommand(CMD_REQUEST_ACTUAL_STATE);
}
}
@@ -589,7 +653,7 @@ extern int gSharedMemoryKey;
class CommonExampleInterface* PhysicsClientCreateFunc(struct CommonExampleOptions& options)
{
PhysicsClientExample* example = new PhysicsClientExample(options.m_guiHelper);
PhysicsClientExample* example = new PhysicsClientExample(options.m_guiHelper, options.m_option);
if (gSharedMemoryKey>=0)
{
example->setSharedMemoryKey(gSharedMemoryKey);

View File

@@ -1,6 +1,13 @@
#ifndef PHYSICS_CLIENT_EXAMPLE_H
#define PHYSICS_CLIENT_EXAMPLE_H
enum ClientExampleOptions
{
eCLIENTEXAMPLE_LOOPBACK=1,
eCLIENTEAXMPLE_DIRECT=2,
eCLIENTEXAMPLE_SERVER=3,
};
class CommonExampleInterface* PhysicsClientCreateFunc(struct CommonExampleOptions& options);
#endif//PHYSICS_CLIENT_EXAMPLE_H

View File

@@ -962,6 +962,13 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
break;
}
case CMD_REQUEST_CAMERA_IMAGE_DATA:
{
serverStatusOut.m_type = CMD_CLIENT_COMMAND_COMPLETED;
hasStatus = true;
break;
}
case CMD_LOAD_URDF:
{

View File

@@ -19,17 +19,18 @@ class PhysicsServerExample : public SharedMemoryCommon
bool m_isConnected;
btClock m_clock;
bool m_replay;
int m_options;
public:
PhysicsServerExample(GUIHelperInterface* helper, SharedMemoryInterface* sharedMem=0);
PhysicsServerExample(GUIHelperInterface* helper, SharedMemoryInterface* sharedMem=0, int options=0);
virtual ~PhysicsServerExample();
virtual void initPhysics();
virtual void stepSimulation(float deltaTime);
void enableCommandLogging()
{
m_physicsServer.enableCommandLogging(true,"BulletPhysicsCommandLog.bin");
@@ -40,9 +41,9 @@ public:
m_replay = true;
m_physicsServer.replayFromLogFile("BulletPhysicsCommandLog.bin");
}
virtual void resetCamera()
{
float dist = 5;
@@ -51,23 +52,23 @@ public:
float targetPos[3]={0,0,0};//-3,2.8,-2.5};
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
}
virtual bool wantsTermination();
virtual bool isConnected();
virtual void renderScene();
virtual void exitPhysics(){}
virtual void physicsDebugDraw(int debugFlags);
btVector3 getRayTo(int x,int y);
virtual bool mouseMoveCallback(float x,float y)
{
if (m_replay)
return false;
CommonRenderInterface* renderer = m_guiHelper->getRenderInterface();
if (!renderer)
{
btAssert(0);
@@ -87,16 +88,16 @@ public:
return false;
CommonRenderInterface* renderer = m_guiHelper->getRenderInterface();
if (!renderer)
{
btAssert(0);
return false;
}
CommonWindowInterface* window = m_guiHelper->getAppInterface()->m_window;
if (state==1)
{
if(button==0 && (!window->isModifierKeyPressed(B3G_ALT) && !window->isModifierKeyPressed(B3G_CONTROL) ))
@@ -133,12 +134,13 @@ public:
};
PhysicsServerExample::PhysicsServerExample(GUIHelperInterface* helper, SharedMemoryInterface* sharedMem)
PhysicsServerExample::PhysicsServerExample(GUIHelperInterface* helper, SharedMemoryInterface* sharedMem, int options)
:SharedMemoryCommon(helper),
m_physicsServer(sharedMem),
m_wantsShutdown(false),
m_isConnected(false),
m_replay(false)
m_replay(false),
m_options(options)
{
b3Printf("Started PhysicsServer\n");
}
@@ -164,18 +166,18 @@ void PhysicsServerExample::initPhysics()
m_guiHelper->setUpAxis(upAxis);
#if 0
createEmptyDynamicsWorld();
//todo: create a special debug drawer that will cache the lines, so we can send the debug info over the wire
btVector3 grav(0,0,0);
grav[upAxis] = 0;//-9.8;
this->m_dynamicsWorld->setGravity(grav);
#endif
m_isConnected = m_physicsServer.connectSharedMemory( m_guiHelper);
}
@@ -188,11 +190,7 @@ bool PhysicsServerExample::wantsTermination()
void PhysicsServerExample::stepSimulation(float deltaTime)
{
if (m_replay)
{
for (int i=0;i<100;i++)
m_physicsServer.processClientCommands();
} else
if (m_options == PHYSICS_SERVER_USE_RTC_CLOCK)
{
btClock rtc;
btScalar endTime = rtc.getTimeMilliseconds() + deltaTime*btScalar(800);
@@ -201,6 +199,10 @@ void PhysicsServerExample::stepSimulation(float deltaTime)
{
m_physicsServer.processClientCommands();
}
} else
{
for (int i=0;i<10;i++)
m_physicsServer.processClientCommands();
}
}
@@ -222,7 +224,7 @@ void PhysicsServerExample::physicsDebugDraw(int debugDrawFlags)
btVector3 PhysicsServerExample::getRayTo(int x,int y)
{
CommonRenderInterface* renderer = m_guiHelper->getRenderInterface();
if (!renderer)
{
btAssert(0);
@@ -288,7 +290,7 @@ extern int gSharedMemoryKey;
class CommonExampleInterface* PhysicsServerCreateFunc(struct CommonExampleOptions& options)
{
PhysicsServerExample* example = new PhysicsServerExample(options.m_guiHelper, options.m_sharedMem);
PhysicsServerExample* example = new PhysicsServerExample(options.m_guiHelper, options.m_sharedMem, options.m_option);
if (gSharedMemoryKey>=0)
{
example->setSharedMemoryKey(gSharedMemoryKey);
@@ -302,5 +304,5 @@ class CommonExampleInterface* PhysicsServerCreateFunc(struct CommonExampleOpt
example->replayFromLogFile();
}
return example;
}

View File

@@ -5,6 +5,7 @@ enum PhysicsServerOptions
{
PHYSICS_SERVER_ENABLE_COMMAND_LOGGING=1,
PHYSICS_SERVER_REPLAY_FROM_COMMAND_LOG=2,
PHYSICS_SERVER_USE_RTC_CLOCK = 4,
};
class CommonExampleInterface* PhysicsServerCreateFunc(struct CommonExampleOptions& options);

View File

@@ -23,6 +23,7 @@ enum EnumSharedMemoryClientCommand
CMD_PICK_BODY,
CMD_MOVE_PICKED_BODY,
CMD_REMOVE_PICKING_CONSTRAINT_BODY,
CMD_REQUEST_CAMERA_IMAGE_DATA,
CMD_MAX_CLIENT_COMMANDS
};
@@ -105,6 +106,14 @@ struct b3DebugLines
const float* m_linesColor;//float red,green,blue times 'm_numDebugLines'.
};
struct b3CameraImageData
{
int m_pixelWidth;
int m_pixelHeight;
const unsigned char* m_rgbColorData;//3*m_pixelWidth*m_pixelHeight bytes
const float* m_depthValues;//m_pixelWidth*m_pixelHeight floats
};
///b3LinkState provides extra information such as the Cartesian world coordinates
///center of mass (COM) of the link, relative to the world reference frame.
///Orientation is a quaternion x,y,z,w
@@ -127,4 +136,5 @@ enum {
CONTROL_MODE_POSITION_VELOCITY_PD,
};
#endif//SHARED_MEMORY_PUBLIC_H

View File

@@ -70,7 +70,8 @@ struct Shader : public IShader {
Vec3f n = (B*m_model->normal(uv)).normalize();
float diff = b3Min(b3Max(0.f, n*m_light_dir_local+0.3f),1.f);
float diff = 1;//b3Min(b3Max(0.f, n*0.3f),1.f);
//float diff = b3Min(b3Max(0.f, n*m_light_dir_local+0.3f),1.f);
//float diff = b3Max(0.f, n*m_light_dir_local);
color = m_model->diffuse(uv)*diff;
@@ -90,11 +91,13 @@ m_userIndex(-1)
{
Vec3f eye(1,1,3);
Vec3f center(0,0,0);
Vec3f up(0,1,0);
Vec3f up(0,0,1);
m_modelMatrix = Matrix::identity();
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);
//m_viewportMatrix = viewport(width/8, height/8, width*3/4, height*3/4);
m_viewportMatrix = viewport(0,0,width,height);
m_projectionMatrix = projection(-1.f/(eye-center).norm());
}
@@ -113,15 +116,22 @@ void TinyRenderObjectData::loadModel(const char* fileName)
}
void TinyRenderObjectData::registerMeshShape(const float* vertices, int numVertices,const int* indices, int numIndices)
void TinyRenderObjectData::registerMeshShape(const float* vertices, int numVertices,const int* indices, int numIndices,
unsigned char* textureImage, int textureWidth, int textureHeight)
{
if (0==m_model)
{
m_model = new Model();
char relativeFileName[1024];
if (b3ResourcePath::findResourcePath("floor_diffuse.tga", relativeFileName, 1024))
if (textureImage)
{
m_model->loadDiffuseTexture(relativeFileName);
m_model->setDiffuseTextureFromData(textureImage,textureWidth,textureHeight);
} else
{
char relativeFileName[1024];
if (b3ResourcePath::findResourcePath("floor_diffuse.tga", relativeFileName, 1024))
{
m_model->loadDiffuseTexture(relativeFileName);
}
}
for (int i=0;i<numVertices;i++)
@@ -223,6 +233,20 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData)
if (0==model)
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);
int width = renderData.m_width;
int height = renderData.m_height;
//renderData.m_viewportMatrix = viewport(width/8, height/8, width*3/4, height*3/4);
renderData.m_viewportMatrix = viewport(0,0,renderData.m_width,renderData.m_height);
//renderData.m_projectionMatrix = projection(-1.f/(eye-center).norm());
b3AlignedObjectArray<float>& zbuffer = renderData.m_depthBuffer;
TGAImage& frame = renderData.m_rgbColorBuffer;
@@ -233,7 +257,10 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData)
Matrix modelViewMatrix = renderData.m_viewMatrix*renderData.m_modelMatrix;
Shader shader(model, light_dir_local, modelViewMatrix, renderData.m_projectionMatrix);
for (int i=0; i<model->nfaces(); i++) {
for (int i=0; i<model->nfaces(); i++) {
for (int j=0; j<3; j++) {
shader.vertex(i, j);
}

View File

@@ -17,6 +17,9 @@ struct TinyRenderObjectData
Matrix m_projectionMatrix;
Matrix m_viewportMatrix;
btVector3 m_eye;
btVector3 m_center;
//Model (vertices, indices, textures, shader)
Matrix m_modelMatrix;
class Model* m_model;
@@ -33,7 +36,8 @@ struct TinyRenderObjectData
void loadModel(const char* fileName);
void createCube(float HalfExtentsX,float HalfExtentsY,float HalfExtentsZ);
void registerMeshShape(const float* vertices, int numVertices,const int* indices, int numIndices);
void registerMeshShape(const float* vertices, int numVertices,const int* indices, int numIndices,
unsigned char* textureImage=0, int textureWidth=0, int textureHeight=0);
void registerMesh2(btAlignedObjectArray<btVector3>& vertices, btAlignedObjectArray<btVector3>& normals,btAlignedObjectArray<int>& indices);

View File

@@ -49,6 +49,28 @@ Model::Model():verts_(), faces_(), norms_(), uv_(), diffusemap_(), normalmap_(),
{
}
void Model::setDiffuseTextureFromData(unsigned char* textureImage,int textureWidth,int textureHeight)
{
diffusemap_ = TGAImage(textureWidth, textureHeight, TGAImage::RGB);
for (int i=0;i<textureWidth;i++)
{
for (int j=0;j<textureHeight;j++)
{
TGAColor color;
color.bgra[0] = textureImage[(i+j*textureWidth)*3+0];
color.bgra[1] = textureImage[(i+j*textureWidth)*3+1];
color.bgra[2] = textureImage[(i+j*textureWidth)*3+2];
color.bgra[3] = 255;
color.bytespp = 3;
diffusemap_.set(i,j,color);
}
}
diffusemap_.flip_vertically();
}
void Model::loadDiffuseTexture(const char* relativeFileName)
{
diffusemap_.read_tga_file(relativeFileName);

View File

@@ -19,6 +19,7 @@ public:
Model(const char *filename);
Model();
void loadDiffuseTexture(const char* relativeFileName);
void setDiffuseTextureFromData(unsigned char* textureImage,int textureWidth,int textureHeight);
void addVertex(float x,float y,float z, float normalX, float normalY, float normalZ, float u, float v);
void addTriangle(int vertexposIndex0, int normalIndex0, int uvIndex0,
int vertexposIndex1, int normalIndex1, int uvIndex1,

View File

@@ -60,8 +60,8 @@ Vec3f barycentric(Vec2f A, Vec2f B, Vec2f C, Vec2f P) {
}
void triangle(mat<4,3,float> &clipc, IShader &shader, TGAImage &image, float *zbuffer, const Matrix& viewPortMatrix) {
mat<3,4,float> pts = (viewPortMatrix*clipc).transpose(); // transposed to ease access to each of the points
mat<3,4,float> pts = (viewPortMatrix*clipc).transpose(); // transposed to ease access to each of the points
//we don't clip triangles that cross the near plane, just discard them instead of showing artifacts
if (pts[0][3]<0 || pts[1][3] <0 || pts[2][3] <0)
@@ -93,8 +93,10 @@ void triangle(mat<4,3,float> &clipc, IShader &shader, TGAImage &image, float *zb
Vec3f bc_clip = Vec3f(bc_screen.x/pts[0][3], bc_screen.y/pts[1][3], bc_screen.z/pts[2][3]);
bc_clip = bc_clip/(bc_clip.x+bc_clip.y+bc_clip.z);
float frag_depth = clipc[2]*bc_clip;
if (bc_screen.x<0 || bc_screen.y<0 || bc_screen.z<0 || zbuffer[P.x+P.y*image.get_width()]>frag_depth) continue;
float frag_depth = -1*(clipc[2]*bc_clip);
if (bc_screen.x<0 || bc_screen.y<0 || bc_screen.z<0 ||
zbuffer[P.x+P.y*image.get_width()]>frag_depth)
continue;
bool discard = shader.fragment(bc_clip, color);
if (!discard) {
zbuffer[P.x+P.y*image.get_width()] = frag_depth;

View File

@@ -8,7 +8,50 @@ INCLUDE_DIRECTORIES(
SET(pybullet_SRCS
pybullet.c
../../examples/ExampleBrowser/ExampleEntries.cpp
../../examples/ExampleBrowser/InProcessExampleBrowser.cpp
../../examples/SharedMemory/InProcessMemory.cpp
../../examples/SharedMemory/PhysicsClient.cpp
../../examples/SharedMemory/PhysicsClient.h
../../examples/SharedMemory/PhysicsServer.cpp
../../examples/SharedMemory/PhysicsServer.h
../../examples/SharedMemory/PhysicsServerExample.cpp
../../examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp
../../examples/SharedMemory/PhysicsServerSharedMemory.cpp
../../examples/SharedMemory/PhysicsServerSharedMemory.h
../../examples/SharedMemory/PhysicsDirect.cpp
../../examples/SharedMemory/PhysicsDirect.h
../../examples/SharedMemory/PhysicsDirectC_API.cpp
../../examples/SharedMemory/PhysicsDirectC_API.h
../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp
../../examples/SharedMemory/PhysicsServerCommandProcessor.h
../../examples/SharedMemory/PhysicsClientSharedMemory.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory.h
../../examples/SharedMemory/PhysicsClientC_API.cpp
../../examples/SharedMemory/PhysicsClientC_API.h
../../examples/SharedMemory/Win32SharedMemory.cpp
../../examples/SharedMemory/Win32SharedMemory.h
../../examples/SharedMemory/PosixSharedMemory.cpp
../../examples/SharedMemory/PosixSharedMemory.h
../../examples/Utils/b3ResourcePath.cpp
../../examples/Utils/b3ResourcePath.h
../../examples/ThirdPartyLibs/tinyxml/tinystr.cpp
../../examples/ThirdPartyLibs/tinyxml/tinyxml.cpp
../../examples/ThirdPartyLibs/tinyxml/tinyxmlerror.cpp
../../examples/ThirdPartyLibs/tinyxml/tinyxmlparser.cpp
../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp
../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.h
../../examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp
../../examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp
../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp
../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp
../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp
../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp
../../examples/Importers/ImportURDFDemo/UrdfParser.cpp
../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp
../../examples/MultiThreading/b3PosixThreadSupport.cpp
../../examples/MultiThreading/b3Win32ThreadSupport.cpp
../../examples/MultiThreading/b3ThreadSupportInterface.cpp
)
IF(WIN32)
@@ -23,7 +66,7 @@ ADD_LIBRARY(pybullet SHARED ${pybullet_SRCS})
SET_TARGET_PROPERTIES(pybullet PROPERTIES VERSION ${BULLET_VERSION})
SET_TARGET_PROPERTIES(pybullet PROPERTIES SOVERSION ${BULLET_VERSION})
TARGET_LINK_LIBRARIES(pybullet BulletExampleBrowserLib BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils BulletInverseDynamics LinearMath OpenGLWindow gwen Bullet3Common ${PYTHON_LIBRARIES})
TARGET_LINK_LIBRARIES(pybullet BulletExampleBrowserLib BulletFileLoader BulletWorldImporter BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils BulletInverseDynamics LinearMath OpenGLWindow gwen Bullet3Common ${PYTHON_LIBRARIES})

View File

@@ -329,10 +329,16 @@ initpybullet(void)
SpamMethods, "Python bindings for Bullet");
#endif
#if PY_MAJOR_VERSION >= 3
if (m == NULL)
return m;
#else
if (m == NULL)
return;
#endif
PyModule_AddIntConstant (m, "SHARED_MEMORY", eCONNECT_SHARED_MEMORY); // user read
PyModule_AddIntConstant (m, "SHARED_MEMORY", eCONNECT_SHARED_MEMORY); // user read
PyModule_AddIntConstant (m, "DIRECT", eCONNECT_DIRECT); // user read
PyModule_AddIntConstant (m, "GUI", eCONNECT_GUI); // user read