mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-13 21:30:09 +00:00
Merge pull request #644 from erwincoumans/master
preparation to receive camera image data from physics server
This commit is contained in:
commit
dcc909133f
@ -11,7 +11,7 @@
|
||||
#include "../Importers/ImportURDFDemo/URDF2Bullet.h"
|
||||
#include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h"
|
||||
#include "../Importers/ImportURDFDemo/URDF2Bullet.h"
|
||||
#include "../Importers/ImportURDFDemo/DefaultVisualShapeConverter.h"
|
||||
|
||||
|
||||
/// Create a btMultiBody model from URDF.
|
||||
/// This is adapted from Bullet URDF loader example
|
||||
@ -45,8 +45,8 @@ public:
|
||||
void init() {
|
||||
this->createEmptyDynamicsWorld();
|
||||
m_dynamicsWorld->setGravity(m_gravity);
|
||||
DefaultVisualShapeConverter visualConverter(&m_nogfx);
|
||||
BulletURDFImporter urdf_importer(&m_nogfx, &visualConverter);
|
||||
|
||||
BulletURDFImporter urdf_importer(&m_nogfx, 0);
|
||||
URDFImporterInterface &u2b(urdf_importer);
|
||||
bool loadOk = u2b.loadURDF(m_filename.c_str(), m_base_fixed);
|
||||
|
||||
|
@ -45,6 +45,8 @@ struct GUIHelperInterface
|
||||
|
||||
virtual void resetCamera(float camDist, float pitch, float yaw, float camPosX,float camPosY, float camPosZ)=0;
|
||||
|
||||
virtual void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int* width, int* height, int* numPixelsCopied)=0;
|
||||
|
||||
virtual void autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld) =0;
|
||||
|
||||
virtual void drawText3D( const char* txt, float posX, float posZY, float posZ, float size)=0;
|
||||
@ -103,6 +105,16 @@ struct DummyGUIHelper : public GUIHelperInterface
|
||||
{
|
||||
}
|
||||
|
||||
virtual void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int* width, int* height, int* numPixelsCopied)
|
||||
{
|
||||
if (width)
|
||||
*width = 0;
|
||||
if (height)
|
||||
*height = 0;
|
||||
if (numPixelsCopied)
|
||||
*numPixelsCopied = 0;
|
||||
}
|
||||
|
||||
virtual void autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld)
|
||||
{
|
||||
}
|
||||
|
@ -76,6 +76,9 @@ struct CommonGraphicsApp
|
||||
|
||||
virtual void dumpNextFrameToPng(const char* pngFilename){}
|
||||
virtual void dumpFramesToVideo(const char* mp4Filename){}
|
||||
|
||||
virtual void getScreenPixels(unsigned char* rgbaBuffer, int bufferSizeInBytes){};
|
||||
|
||||
virtual void getBackgroundColor(float* red, float* green, float* blue) const
|
||||
{
|
||||
if (red)
|
||||
|
@ -124,6 +124,8 @@ SET(BulletExampleBrowser_SRCS
|
||||
../TinyRenderer/tgaimage.cpp
|
||||
../TinyRenderer/our_gl.cpp
|
||||
../TinyRenderer/TinyRenderer.cpp
|
||||
../SharedMemory/TinyRendererVisualShapeConverter.cpp
|
||||
../SharedMemory/TinyRendererVisualShapeConverter.h
|
||||
../RenderingExamples/TinyRendererSetup.cpp
|
||||
../SharedMemory/PhysicsServer.cpp
|
||||
../SharedMemory/PhysicsClientSharedMemory.cpp
|
||||
@ -246,8 +248,6 @@ SET(BulletExampleBrowser_SRCS
|
||||
../Importers/ImportURDFDemo/urdfStringSplit.h
|
||||
../Importers/ImportURDFDemo/BulletUrdfImporter.cpp
|
||||
../Importers/ImportURDFDemo/BulletUrdfImporter.h
|
||||
../Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp
|
||||
../Importers/ImportURDFDemo/DefaultVisualShapeConverter.h
|
||||
../VoronoiFracture/VoronoiFractureDemo.cpp
|
||||
../VoronoiFracture/VoronoiFractureDemo.h
|
||||
../VoronoiFracture/btConvexConvexMprAlgorithm.cpp
|
||||
|
@ -143,6 +143,9 @@ struct OpenGLGuiHelperInternalData
|
||||
struct CommonGraphicsApp* m_glApp;
|
||||
class MyDebugDrawer* m_debugDraw;
|
||||
GL_ShapeDrawer* m_gl2ShapeDrawer;
|
||||
|
||||
btAlignedObjectArray<unsigned char> m_rgbaPixelBuffer;
|
||||
btAlignedObjectArray<float> m_depthBuffer;
|
||||
};
|
||||
|
||||
|
||||
@ -323,6 +326,51 @@ void OpenGLGuiHelper::resetCamera(float camDist, float pitch, float yaw, float c
|
||||
}
|
||||
|
||||
|
||||
void OpenGLGuiHelper::copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied)
|
||||
{
|
||||
int w = m_data->m_glApp->m_window->getWidth();
|
||||
int h = m_data->m_glApp->m_window->getHeight();
|
||||
|
||||
if (widthPtr)
|
||||
*widthPtr = w;
|
||||
if (heightPtr)
|
||||
*heightPtr = h;
|
||||
if (numPixelsCopied)
|
||||
*numPixelsCopied = 0;
|
||||
|
||||
int numTotalPixels = w*h;
|
||||
int numRemainingPixels = numTotalPixels - startPixelIndex;
|
||||
int numBytesPerPixel = 4;//RGBA
|
||||
int numRequestedPixels = btMin(rgbaBufferSizeInPixels,numRemainingPixels);
|
||||
if (numRequestedPixels)
|
||||
{
|
||||
if (startPixelIndex==0)
|
||||
{
|
||||
|
||||
//quick test: render the scene
|
||||
getRenderInterface()->renderScene();
|
||||
//copy the image into our local cache
|
||||
m_data->m_rgbaPixelBuffer.resize(w*h*numBytesPerPixel);
|
||||
m_data->m_depthBuffer.resize(w*h);
|
||||
m_data->m_glApp->getScreenPixels(&(m_data->m_rgbaPixelBuffer[0]),m_data->m_rgbaPixelBuffer.size());
|
||||
}
|
||||
for (int i=0;i<numRequestedPixels*numBytesPerPixel;i++)
|
||||
{
|
||||
if (pixelsRGBA)
|
||||
{
|
||||
pixelsRGBA[i] = m_data->m_rgbaPixelBuffer[i+startPixelIndex*numBytesPerPixel];
|
||||
}
|
||||
}
|
||||
|
||||
if (numPixelsCopied)
|
||||
*numPixelsCopied = numRequestedPixels;
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
struct MyConvertPointerSizeT
|
||||
|
@ -45,6 +45,8 @@ struct OpenGLGuiHelper : public GUIHelperInterface
|
||||
|
||||
virtual void resetCamera(float camDist, float pitch, float yaw, float camPosX,float camPosY, float camPosZ);
|
||||
|
||||
virtual void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int* width, int* height, int* numPixelsCopied);
|
||||
|
||||
virtual void autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld) ;
|
||||
|
||||
virtual void drawText3D( const char* txt, float posX, float posY, float posZ, float size);
|
||||
|
@ -76,6 +76,8 @@ project "App_BulletExampleBrowser"
|
||||
"../SharedMemory/PhysicsLoopBackC_API.h",
|
||||
"../SharedMemory/PhysicsServerCommandProcessor.cpp",
|
||||
"../SharedMemory/PhysicsServerCommandProcessor.h",
|
||||
"../SharedMemory/TinyRendererVisualShapeConverter.cpp",
|
||||
"../SharedMemory/TinyRendererVisualShapeConverter.h",
|
||||
"../MultiThreading/MultiThreadingExample.cpp",
|
||||
"../MultiThreading/b3PosixThreadSupport.cpp",
|
||||
"../MultiThreading/b3Win32ThreadSupport.cpp",
|
||||
|
@ -34,7 +34,6 @@ files {
|
||||
"../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",
|
||||
@ -86,7 +85,6 @@ files {
|
||||
"../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",
|
||||
@ -151,7 +149,6 @@ files {
|
||||
"../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",
|
||||
@ -212,7 +209,6 @@ files {
|
||||
"../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",
|
||||
|
@ -12,7 +12,7 @@
|
||||
#include "../../Utils/b3ResourcePath.h"
|
||||
|
||||
#include "../ImportURDFDemo/BulletUrdfImporter.h"
|
||||
#include "../Importers/ImportURDFDemo/DefaultVisualShapeConverter.h"
|
||||
|
||||
|
||||
#include "../ImportURDFDemo/URDF2Bullet.h"
|
||||
|
||||
@ -203,8 +203,8 @@ void ImportSDFSetup::initPhysics()
|
||||
|
||||
m_dynamicsWorld->setGravity(gravity);
|
||||
|
||||
DefaultVisualShapeConverter visualConverter(m_guiHelper);
|
||||
BulletURDFImporter u2b(m_guiHelper, &visualConverter);
|
||||
|
||||
BulletURDFImporter u2b(m_guiHelper, 0);
|
||||
|
||||
bool loadOk = u2b.loadSDF(m_fileName);
|
||||
|
||||
|
@ -37,7 +37,7 @@ struct BulletURDFInternalData
|
||||
UrdfParser m_urdfParser;
|
||||
struct GUIHelperInterface* m_guiHelper;
|
||||
char m_pathPrefix[1024];
|
||||
|
||||
btHashMap<btHashInt,btVector4> m_linkColors;
|
||||
btAlignedObjectArray<btCollisionShape*> m_allocatedCollisionShapes;
|
||||
|
||||
LinkVisualShapesConverter* m_customVisualShapesConverter;
|
||||
@ -232,14 +232,6 @@ void BulletURDFImporter::getLinkChildIndices(int linkIndex, btAlignedObjectArray
|
||||
}
|
||||
}
|
||||
|
||||
bool BulletURDFImporter::getLinkColor(int linkIndex, btVector4& colorRGBA) const
|
||||
{
|
||||
if (m_data->m_customVisualShapesConverter)
|
||||
{
|
||||
return m_data->m_customVisualShapesConverter->getLinkColor(linkIndex, colorRGBA);
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
std::string BulletURDFImporter::getLinkName(int linkIndex) const
|
||||
{
|
||||
@ -585,16 +577,385 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co
|
||||
return shape;
|
||||
}
|
||||
|
||||
int BulletURDFImporter::convertLinkVisualShapes2(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, class btCollisionShape* colShape) const
|
||||
|
||||
static void convertURDFToVisualShapeInternal(const UrdfVisual* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray<GLInstanceVertex>& verticesOut, btAlignedObjectArray<int>& indicesOut)
|
||||
{
|
||||
|
||||
|
||||
GLInstanceGraphicsShape* glmesh = 0;
|
||||
|
||||
btConvexShape* convexColShape = 0;
|
||||
|
||||
switch (visual->m_geometry.m_type)
|
||||
{
|
||||
case URDF_GEOM_CYLINDER:
|
||||
{
|
||||
btAlignedObjectArray<btVector3> vertices;
|
||||
|
||||
//int numVerts = sizeof(barrel_vertices)/(9*sizeof(float));
|
||||
int numSteps = 32;
|
||||
for (int i = 0; i<numSteps; i++)
|
||||
{
|
||||
|
||||
btScalar cylRadius = visual->m_geometry.m_cylinderRadius;
|
||||
btScalar cylLength = visual->m_geometry.m_cylinderLength;
|
||||
|
||||
btVector3 vert(cylRadius*btSin(SIMD_2_PI*(float(i) / numSteps)), cylRadius*btCos(SIMD_2_PI*(float(i) / numSteps)), cylLength / 2.);
|
||||
vertices.push_back(vert);
|
||||
vert[2] = -cylLength / 2.;
|
||||
vertices.push_back(vert);
|
||||
}
|
||||
|
||||
btConvexHullShape* cylZShape = new btConvexHullShape(&vertices[0].x(), vertices.size(), sizeof(btVector3));
|
||||
cylZShape->setMargin(0.001);
|
||||
convexColShape = cylZShape;
|
||||
break;
|
||||
}
|
||||
case URDF_GEOM_BOX:
|
||||
{
|
||||
|
||||
btVector3 extents = visual->m_geometry.m_boxSize;
|
||||
|
||||
btBoxShape* boxShape = new btBoxShape(extents*0.5f);
|
||||
//btConvexShape* boxShape = new btConeShapeX(extents[2]*0.5,extents[0]*0.5);
|
||||
convexColShape = boxShape;
|
||||
convexColShape->setMargin(0.001);
|
||||
break;
|
||||
}
|
||||
case URDF_GEOM_SPHERE:
|
||||
{
|
||||
btScalar radius = visual->m_geometry.m_sphereRadius;
|
||||
btSphereShape* sphereShape = new btSphereShape(radius);
|
||||
convexColShape = sphereShape;
|
||||
convexColShape->setMargin(0.001);
|
||||
break;
|
||||
|
||||
break;
|
||||
}
|
||||
case URDF_GEOM_MESH:
|
||||
{
|
||||
if (visual->m_name.length())
|
||||
{
|
||||
//b3Printf("visual->name=%s\n", visual->m_name.c_str());
|
||||
}
|
||||
if (1)//visual->m_geometry)
|
||||
{
|
||||
if (visual->m_geometry.m_meshFileName.length())
|
||||
{
|
||||
const char* filename = visual->m_geometry.m_meshFileName.c_str();
|
||||
//b3Printf("mesh->filename=%s\n", filename);
|
||||
char fullPath[1024];
|
||||
int fileType = 0;
|
||||
|
||||
char tmpPathPrefix[1024];
|
||||
std::string xml_string;
|
||||
int maxPathLen = 1024;
|
||||
b3FileUtils::extractPath(filename,tmpPathPrefix,maxPathLen);
|
||||
|
||||
char visualPathPrefix[1024];
|
||||
sprintf(visualPathPrefix,"%s%s",urdfPathPrefix,tmpPathPrefix);
|
||||
|
||||
|
||||
sprintf(fullPath, "%s%s", urdfPathPrefix, filename);
|
||||
b3FileUtils::toLower(fullPath);
|
||||
if (strstr(fullPath, ".dae"))
|
||||
{
|
||||
fileType = FILE_COLLADA;
|
||||
}
|
||||
if (strstr(fullPath, ".stl"))
|
||||
{
|
||||
fileType = FILE_STL;
|
||||
}
|
||||
if (strstr(fullPath,".obj"))
|
||||
{
|
||||
fileType = FILE_OBJ;
|
||||
}
|
||||
|
||||
|
||||
sprintf(fullPath, "%s%s", urdfPathPrefix, filename);
|
||||
FILE* f = fopen(fullPath, "rb");
|
||||
if (f)
|
||||
{
|
||||
fclose(f);
|
||||
|
||||
switch (fileType)
|
||||
{
|
||||
case FILE_OBJ:
|
||||
{
|
||||
glmesh = LoadMeshFromObj(fullPath,visualPathPrefix);
|
||||
break;
|
||||
}
|
||||
|
||||
case FILE_STL:
|
||||
{
|
||||
glmesh = LoadMeshFromSTL(fullPath);
|
||||
break;
|
||||
}
|
||||
case FILE_COLLADA:
|
||||
{
|
||||
|
||||
btAlignedObjectArray<GLInstanceGraphicsShape> visualShapes;
|
||||
btAlignedObjectArray<ColladaGraphicsInstance> visualShapeInstances;
|
||||
btTransform upAxisTrans; upAxisTrans.setIdentity();
|
||||
float unitMeterScaling = 1;
|
||||
int upAxis = 2;
|
||||
|
||||
LoadMeshFromCollada(fullPath,
|
||||
visualShapes,
|
||||
visualShapeInstances,
|
||||
upAxisTrans,
|
||||
unitMeterScaling,
|
||||
upAxis);
|
||||
|
||||
glmesh = new GLInstanceGraphicsShape;
|
||||
// int index = 0;
|
||||
glmesh->m_indices = new b3AlignedObjectArray<int>();
|
||||
glmesh->m_vertices = new b3AlignedObjectArray<GLInstanceVertex>();
|
||||
|
||||
for (int i = 0; i<visualShapeInstances.size(); i++)
|
||||
{
|
||||
ColladaGraphicsInstance* instance = &visualShapeInstances[i];
|
||||
GLInstanceGraphicsShape* gfxShape = &visualShapes[instance->m_shapeIndex];
|
||||
|
||||
b3AlignedObjectArray<GLInstanceVertex> verts;
|
||||
verts.resize(gfxShape->m_vertices->size());
|
||||
|
||||
int baseIndex = glmesh->m_vertices->size();
|
||||
|
||||
for (int i = 0; i<gfxShape->m_vertices->size(); i++)
|
||||
{
|
||||
verts[i].normal[0] = gfxShape->m_vertices->at(i).normal[0];
|
||||
verts[i].normal[1] = gfxShape->m_vertices->at(i).normal[1];
|
||||
verts[i].normal[2] = gfxShape->m_vertices->at(i).normal[2];
|
||||
verts[i].uv[0] = gfxShape->m_vertices->at(i).uv[0];
|
||||
verts[i].uv[1] = gfxShape->m_vertices->at(i).uv[1];
|
||||
verts[i].xyzw[0] = gfxShape->m_vertices->at(i).xyzw[0];
|
||||
verts[i].xyzw[1] = gfxShape->m_vertices->at(i).xyzw[1];
|
||||
verts[i].xyzw[2] = gfxShape->m_vertices->at(i).xyzw[2];
|
||||
verts[i].xyzw[3] = gfxShape->m_vertices->at(i).xyzw[3];
|
||||
|
||||
}
|
||||
|
||||
int curNumIndices = glmesh->m_indices->size();
|
||||
int additionalIndices = gfxShape->m_indices->size();
|
||||
glmesh->m_indices->resize(curNumIndices + additionalIndices);
|
||||
for (int k = 0; k<additionalIndices; k++)
|
||||
{
|
||||
glmesh->m_indices->at(curNumIndices + k) = gfxShape->m_indices->at(k) + baseIndex;
|
||||
}
|
||||
|
||||
//compensate upAxisTrans and unitMeterScaling here
|
||||
btMatrix4x4 upAxisMat;
|
||||
upAxisMat.setIdentity();
|
||||
// upAxisMat.setPureRotation(upAxisTrans.getRotation());
|
||||
btMatrix4x4 unitMeterScalingMat;
|
||||
unitMeterScalingMat.setPureScaling(btVector3(unitMeterScaling, unitMeterScaling, unitMeterScaling));
|
||||
btMatrix4x4 worldMat = unitMeterScalingMat*upAxisMat*instance->m_worldTransform;
|
||||
//btMatrix4x4 worldMat = instance->m_worldTransform;
|
||||
int curNumVertices = glmesh->m_vertices->size();
|
||||
int additionalVertices = verts.size();
|
||||
glmesh->m_vertices->reserve(curNumVertices + additionalVertices);
|
||||
|
||||
for (int v = 0; v<verts.size(); v++)
|
||||
{
|
||||
btVector3 pos(verts[v].xyzw[0], verts[v].xyzw[1], verts[v].xyzw[2]);
|
||||
pos = worldMat*pos;
|
||||
verts[v].xyzw[0] = float(pos[0]);
|
||||
verts[v].xyzw[1] = float(pos[1]);
|
||||
verts[v].xyzw[2] = float(pos[2]);
|
||||
glmesh->m_vertices->push_back(verts[v]);
|
||||
}
|
||||
}
|
||||
glmesh->m_numIndices = glmesh->m_indices->size();
|
||||
glmesh->m_numvertices = glmesh->m_vertices->size();
|
||||
//glmesh = LoadMeshFromCollada(fullPath);
|
||||
|
||||
break;
|
||||
}
|
||||
default:
|
||||
{
|
||||
b3Warning("Error: unsupported file type for Visual mesh: %s\n", fullPath);
|
||||
btAssert(0);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
if (glmesh && glmesh->m_vertices && (glmesh->m_numvertices>0))
|
||||
{
|
||||
//apply the geometry scaling
|
||||
for (int i=0;i<glmesh->m_vertices->size();i++)
|
||||
{
|
||||
glmesh->m_vertices->at(i).xyzw[0] *= visual->m_geometry.m_meshScale[0];
|
||||
glmesh->m_vertices->at(i).xyzw[1] *= visual->m_geometry.m_meshScale[1];
|
||||
glmesh->m_vertices->at(i).xyzw[2] *= visual->m_geometry.m_meshScale[2];
|
||||
}
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
b3Warning("issue extracting mesh from COLLADA/STL file %s\n", fullPath);
|
||||
}
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
b3Warning("mesh geometry not found %s\n", fullPath);
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
break;
|
||||
}
|
||||
default:
|
||||
{
|
||||
b3Warning("Error: unknown visual geometry type\n");
|
||||
}
|
||||
}
|
||||
|
||||
//if we have a convex, tesselate into localVertices/localIndices
|
||||
if ((glmesh==0) && convexColShape)
|
||||
{
|
||||
btShapeHull* hull = new btShapeHull(convexColShape);
|
||||
hull->buildHull(0.0);
|
||||
{
|
||||
// int strideInBytes = 9*sizeof(float);
|
||||
int numVertices = hull->numVertices();
|
||||
int numIndices = hull->numIndices();
|
||||
|
||||
|
||||
glmesh = new GLInstanceGraphicsShape;
|
||||
// int index = 0;
|
||||
glmesh->m_indices = new b3AlignedObjectArray<int>();
|
||||
glmesh->m_vertices = new b3AlignedObjectArray<GLInstanceVertex>();
|
||||
|
||||
|
||||
for (int i = 0; i < numVertices; i++)
|
||||
{
|
||||
GLInstanceVertex vtx;
|
||||
btVector3 pos = hull->getVertexPointer()[i];
|
||||
vtx.xyzw[0] = pos.x();
|
||||
vtx.xyzw[1] = pos.y();
|
||||
vtx.xyzw[2] = pos.z();
|
||||
vtx.xyzw[3] = 1.f;
|
||||
pos.normalize();
|
||||
vtx.normal[0] = pos.x();
|
||||
vtx.normal[1] = pos.y();
|
||||
vtx.normal[2] = pos.z();
|
||||
vtx.uv[0] = 0.5f;
|
||||
vtx.uv[1] = 0.5f;
|
||||
glmesh->m_vertices->push_back(vtx);
|
||||
}
|
||||
|
||||
btAlignedObjectArray<int> indices;
|
||||
for (int i = 0; i < numIndices; i++)
|
||||
{
|
||||
glmesh->m_indices->push_back(hull->getIndexPointer()[i]);
|
||||
}
|
||||
|
||||
glmesh->m_numvertices = glmesh->m_vertices->size();
|
||||
glmesh->m_numIndices = glmesh->m_indices->size();
|
||||
}
|
||||
delete hull;
|
||||
delete convexColShape;
|
||||
convexColShape = 0;
|
||||
|
||||
}
|
||||
|
||||
if (glmesh && glmesh->m_numIndices>0 && glmesh->m_numvertices >0)
|
||||
{
|
||||
|
||||
int baseIndex = verticesOut.size();
|
||||
|
||||
|
||||
|
||||
for (int i = 0; i < glmesh->m_indices->size(); i++)
|
||||
{
|
||||
indicesOut.push_back(glmesh->m_indices->at(i) + baseIndex);
|
||||
}
|
||||
|
||||
for (int i = 0; i < glmesh->m_vertices->size(); i++)
|
||||
{
|
||||
GLInstanceVertex& v = glmesh->m_vertices->at(i);
|
||||
btVector3 vert(v.xyzw[0],v.xyzw[1],v.xyzw[2]);
|
||||
btVector3 vt = visualTransform*vert;
|
||||
v.xyzw[0] = vt[0];
|
||||
v.xyzw[1] = vt[1];
|
||||
v.xyzw[2] = vt[2];
|
||||
btVector3 triNormal(v.normal[0],v.normal[1],v.normal[2]);
|
||||
triNormal = visualTransform.getBasis()*triNormal;
|
||||
v.normal[0] = triNormal[0];
|
||||
v.normal[1] = triNormal[1];
|
||||
v.normal[2] = triNormal[2];
|
||||
verticesOut.push_back(v);
|
||||
}
|
||||
}
|
||||
delete glmesh;
|
||||
|
||||
}
|
||||
|
||||
|
||||
int BulletURDFImporter::convertLinkVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame) const
|
||||
{
|
||||
int graphicsIndex = -1;
|
||||
btAlignedObjectArray<GLInstanceVertex> vertices;
|
||||
btAlignedObjectArray<int> indices;
|
||||
btTransform startTrans; startTrans.setIdentity();
|
||||
|
||||
const UrdfModel& model = m_data->m_urdfParser.getModel();
|
||||
UrdfLink* const* linkPtr = model.m_links.getAtIndex(linkIndex);
|
||||
if (linkPtr)
|
||||
{
|
||||
|
||||
const UrdfLink* link = *linkPtr;
|
||||
|
||||
for (int v = 0; v < link->m_visualArray.size();v++)
|
||||
{
|
||||
const UrdfVisual& vis = link->m_visualArray[v];
|
||||
btTransform childTrans = vis.m_linkLocalFrame;
|
||||
btHashString matName(vis.m_materialName.c_str());
|
||||
UrdfMaterial *const * matPtr = model.m_materials[matName];
|
||||
if (matPtr)
|
||||
{
|
||||
UrdfMaterial *const mat = *matPtr;
|
||||
//printf("UrdfMaterial %s, rgba = %f,%f,%f,%f\n",mat->m_name.c_str(),mat->m_rgbaColor[0],mat->m_rgbaColor[1],mat->m_rgbaColor[2],mat->m_rgbaColor[3]);
|
||||
m_data->m_linkColors.insert(linkIndex,mat->m_rgbaColor);
|
||||
}
|
||||
convertURDFToVisualShapeInternal(&vis, pathPrefix, localInertiaFrame.inverse()*childTrans, vertices, indices);
|
||||
|
||||
|
||||
}
|
||||
}
|
||||
if (vertices.size() && indices.size())
|
||||
{
|
||||
graphicsIndex = m_data->m_guiHelper->registerGraphicsShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size());
|
||||
}
|
||||
return graphicsIndex;
|
||||
}
|
||||
|
||||
|
||||
bool BulletURDFImporter::getLinkColor(int linkIndex, btVector4& colorRGBA) const
|
||||
{
|
||||
const btVector4* rgbaPtr = m_data->m_linkColors[linkIndex];
|
||||
if (rgbaPtr)
|
||||
{
|
||||
colorRGBA = *rgbaPtr;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
|
||||
void BulletURDFImporter::convertLinkVisualShapes2(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, class btCollisionObject* colObj) const
|
||||
{
|
||||
int graphicsIndex = -1;
|
||||
|
||||
if (m_data->m_customVisualShapesConverter)
|
||||
{
|
||||
const UrdfModel& model = m_data->m_urdfParser.getModel();
|
||||
graphicsIndex = m_data->m_customVisualShapesConverter->convertVisualShapes(linkIndex,pathPrefix,localInertiaFrame, model, colShape);
|
||||
m_data->m_customVisualShapesConverter->convertVisualShapes(linkIndex,pathPrefix,localInertiaFrame, model, colObj);
|
||||
}
|
||||
return graphicsIndex;
|
||||
|
||||
}
|
||||
|
||||
|
@ -46,7 +46,9 @@ public:
|
||||
|
||||
virtual bool getRootTransformInWorld(btTransform& rootTransformInWorld) const;
|
||||
|
||||
virtual int convertLinkVisualShapes2(int linkIndex, const char* pathPrefix, const btTransform& inertialFrame, class btCollisionShape* colShape) const;
|
||||
virtual int convertLinkVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& inertialFrame) const;
|
||||
|
||||
virtual void convertLinkVisualShapes2(int linkIndex, const char* pathPrefix, const btTransform& inertialFrame, class btCollisionObject* colObj) const;
|
||||
|
||||
///todo(erwincoumans) refactor this convertLinkCollisionShapes/memory allocation
|
||||
|
||||
@ -55,6 +57,7 @@ public:
|
||||
virtual int getNumAllocatedCollisionShapes() const;
|
||||
virtual class btCollisionShape* getAllocatedCollisionShape(int index);
|
||||
|
||||
|
||||
};
|
||||
|
||||
|
||||
|
@ -1,26 +0,0 @@
|
||||
#ifndef DEFAULT_VISUAL_SHAPE_CONVERTER_H
|
||||
#define DEFAULT_VISUAL_SHAPE_CONVERTER_H
|
||||
|
||||
|
||||
#include "LinkVisualShapesConverter.h"
|
||||
|
||||
struct DefaultVisualShapeConverter : public LinkVisualShapesConverter
|
||||
{
|
||||
|
||||
struct DefaultVisualShapeConverterInternalData* m_data;
|
||||
|
||||
DefaultVisualShapeConverter(struct GUIHelperInterface* guiHelper);
|
||||
|
||||
virtual ~DefaultVisualShapeConverter();
|
||||
|
||||
virtual int convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfModel& model, class btCollisionShape* colShape);
|
||||
|
||||
virtual bool getLinkColor(int linkIndex, btVector4& colorRGBA) const;
|
||||
|
||||
|
||||
};
|
||||
|
||||
|
||||
|
||||
|
||||
#endif //DEFAULT_VISUAL_SHAPE_CONVERTER_H
|
@ -10,7 +10,7 @@
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h"
|
||||
#include "../CommonInterfaces/CommonParameterInterface.h"
|
||||
#include "../../Utils/b3ResourcePath.h"
|
||||
#include "DefaultVisualShapeConverter.h"
|
||||
|
||||
|
||||
#include "BulletUrdfImporter.h"
|
||||
|
||||
@ -200,9 +200,7 @@ void ImportUrdfSetup::initPhysics()
|
||||
|
||||
m_dynamicsWorld->setGravity(gravity);
|
||||
|
||||
|
||||
DefaultVisualShapeConverter visualConverter(m_guiHelper);
|
||||
BulletURDFImporter u2b(m_guiHelper, &visualConverter);
|
||||
BulletURDFImporter u2b(m_guiHelper, 0);
|
||||
|
||||
|
||||
bool loadOk = u2b.loadURDF(m_fileName);
|
||||
|
@ -3,8 +3,7 @@
|
||||
|
||||
struct LinkVisualShapesConverter
|
||||
{
|
||||
virtual int convertVisualShapes(int linkIndex, const char* pathPrefix, const class btTransform& localInertiaFrame, const struct UrdfModel& model, class btCollisionShape* colShape)=0;
|
||||
virtual bool getLinkColor(int linkIndex, class btVector4& colorRGBA) const = 0;
|
||||
virtual void convertVisualShapes(int linkIndex, const char* pathPrefix, const class btTransform& localInertiaFrame, const struct UrdfModel& model, class btCollisionObject* colObj)=0;
|
||||
};
|
||||
|
||||
#endif //LINK_VISUAL_SHAPES_CONVERTER_H
|
||||
|
@ -213,7 +213,9 @@ void ConvertURDF2BulletInternal(const URDFImporterInterface& u2b, MultiBodyCreat
|
||||
|
||||
btCompoundShape* compoundShape = u2b.convertLinkCollisionShapes(urdfLinkIndex,pathPrefix,localInertialFrame);
|
||||
|
||||
int graphicsIndex = u2b.convertLinkVisualShapes2(urdfLinkIndex,pathPrefix,localInertialFrame,compoundShape);
|
||||
int graphicsIndex = u2b.convertLinkVisualShapes(urdfLinkIndex,pathPrefix,localInertialFrame);
|
||||
|
||||
|
||||
|
||||
|
||||
if (compoundShape)
|
||||
@ -246,6 +248,8 @@ void ConvertURDF2BulletInternal(const URDFImporterInterface& u2b, MultiBodyCreat
|
||||
|
||||
creation.createRigidBodyGraphicsInstance(urdfLinkIndex, body, color, graphicsIndex);
|
||||
cache.registerRigidBody(urdfLinkIndex, body, inertialFrameInWorldSpace, mass, localInertiaDiagonal, compoundShape, localInertialFrame);
|
||||
|
||||
//untested: u2b.convertLinkVisualShapes2(urdfLinkIndex,pathPrefix,localInertialFrame,body);
|
||||
} else
|
||||
{
|
||||
if (cache.m_bulletMultiBody==0)
|
||||
@ -386,6 +390,8 @@ void ConvertURDF2BulletInternal(const URDFImporterInterface& u2b, MultiBodyCreat
|
||||
u2b.getLinkColor(urdfLinkIndex,color);
|
||||
creation.createCollisionObjectGraphicsInstance(urdfLinkIndex,col,color);
|
||||
|
||||
u2b.convertLinkVisualShapes2(urdfLinkIndex,pathPrefix,localInertialFrame,col);
|
||||
|
||||
btScalar friction = 0.5f;
|
||||
|
||||
col->setFriction(friction);
|
||||
@ -398,6 +404,9 @@ void ConvertURDF2BulletInternal(const URDFImporterInterface& u2b, MultiBodyCreat
|
||||
cache.m_bulletMultiBody->setBaseCollider(col);
|
||||
}
|
||||
}
|
||||
} else
|
||||
{
|
||||
//u2b.convertLinkVisualShapes2(urdfLinkIndex,pathPrefix,localInertialFrame,compoundShape);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -44,7 +44,7 @@ public:
|
||||
///quick hack: need to rethink the API/dependencies of this
|
||||
virtual int convertLinkVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& inertialFrame) const { return -1;}
|
||||
|
||||
virtual int convertLinkVisualShapes2(int linkIndex, const char* pathPrefix, const btTransform& inertialFrame, class btCollisionShape* colShape) const { return -1;}
|
||||
virtual void convertLinkVisualShapes2(int linkIndex, const char* pathPrefix, const btTransform& inertialFrame, class btCollisionObject* colObj) const { }
|
||||
|
||||
virtual class btCompoundShape* convertLinkCollisionShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame) const = 0;
|
||||
};
|
||||
|
@ -23,7 +23,6 @@ subject to the following restrictions:
|
||||
#include "../Importers/ImportURDFDemo/BulletUrdfImporter.h"
|
||||
#include "../Importers/ImportURDFDemo/URDF2Bullet.h"
|
||||
#include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h"
|
||||
#include "../Importers/ImportURDFDemo/DefaultVisualShapeConverter.h"
|
||||
|
||||
#include "../CommonInterfaces/CommonMultiBodyBase.h"
|
||||
|
||||
@ -156,8 +155,8 @@ void InverseDynamicsExample::initPhysics()
|
||||
{
|
||||
|
||||
|
||||
DefaultVisualShapeConverter visualConverter(m_guiHelper);
|
||||
BulletURDFImporter u2b(m_guiHelper, &visualConverter);
|
||||
|
||||
BulletURDFImporter u2b(m_guiHelper,0);
|
||||
bool loadOk = u2b.loadURDF("kuka_lwr/kuka.urdf");
|
||||
if (loadOk)
|
||||
{
|
||||
|
@ -34,7 +34,6 @@ files {
|
||||
"../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",
|
||||
@ -86,7 +85,6 @@ files {
|
||||
"../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",
|
||||
@ -151,7 +149,6 @@ files {
|
||||
"../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",
|
||||
@ -210,7 +207,6 @@ files {
|
||||
"../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",
|
||||
|
@ -19,7 +19,7 @@ subject to the following restrictions:
|
||||
bool useShadowMap=true;//false;//true;
|
||||
int shadowMapWidth=8192;
|
||||
int shadowMapHeight=8192;
|
||||
float shadowMapWorldSize=10;
|
||||
float shadowMapWorldSize=50;
|
||||
|
||||
#define MAX_POINTS_IN_BATCH 1024
|
||||
#define MAX_LINES_IN_BATCH 1024
|
||||
|
@ -657,6 +657,19 @@ SimpleOpenGL3App::~SimpleOpenGL3App()
|
||||
delete m_data ;
|
||||
}
|
||||
|
||||
void SimpleOpenGL3App::getScreenPixels(unsigned char* rgbaBuffer, int bufferSizeInBytes)
|
||||
{
|
||||
int width = (int)m_window->getRetinaScale()*m_instancingRenderer->getScreenWidth();
|
||||
int height = (int)m_window->getRetinaScale()*m_instancingRenderer->getScreenHeight();
|
||||
if ((width*height*4) == bufferSizeInBytes)
|
||||
{
|
||||
glReadPixels(0,0,width, height, GL_RGBA, GL_UNSIGNED_BYTE, rgbaBuffer);
|
||||
int glstat = glGetError();
|
||||
b3Assert(glstat==GL_NO_ERROR);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
//#define STB_IMAGE_WRITE_IMPLEMENTATION
|
||||
#include "stb_image_write.h"
|
||||
static void writeTextureToFile(int textureWidth, int textureHeight, const char* fileName, FILE* ffmpegVideo)
|
||||
|
@ -24,6 +24,7 @@ struct SimpleOpenGL3App : public CommonGraphicsApp
|
||||
virtual void registerGrid(int xres, int yres, float color0[4], float color1[4]);
|
||||
void dumpNextFrameToPng(const char* pngFilename);
|
||||
void dumpFramesToVideo(const char* mp4Filename);
|
||||
void getScreenPixels(unsigned char* rgbaBuffer, int bufferSizeInBytes);
|
||||
|
||||
void drawGrid(DrawGridData data=DrawGridData());
|
||||
virtual void setUpAxis(int axis);
|
||||
|
@ -718,15 +718,6 @@ void Win32Window::runMainLoop()
|
||||
void Win32Window::startRendering()
|
||||
{
|
||||
pumpMessage();
|
||||
|
||||
// glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT | GL_STENCIL_BUFFER_BIT); //clear buffers
|
||||
|
||||
//glCullFace(GL_BACK);
|
||||
//glFrontFace(GL_CCW);
|
||||
// glEnable(GL_DEPTH_TEST);
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
@ -37,6 +37,9 @@ public:
|
||||
virtual const float* getDebugLinesFrom() const = 0;
|
||||
virtual const float* getDebugLinesTo() const = 0;
|
||||
virtual const float* getDebugLinesColor() const = 0;
|
||||
|
||||
virtual void getCachedCameraImage(struct b3CameraImageData* cameraData)=0;
|
||||
|
||||
};
|
||||
|
||||
#endif // BT_PHYSICS_CLIENT_API_H
|
||||
|
@ -686,17 +686,23 @@ b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physC
|
||||
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
|
||||
b3Assert(command);
|
||||
command->m_type =CMD_REQUEST_CAMERA_IMAGE_DATA;
|
||||
command->m_requestPixelDataArguments.m_startPixelIndex = 0;
|
||||
command->m_updateFlags = REQUEST_PIXEL_ARGS_USE_HARDWARE_OPENGL;
|
||||
return (b3SharedMemoryCommandHandle) command;
|
||||
}
|
||||
|
||||
void b3RequestCameraImageSetResolution(b3SharedMemoryCommandHandle command, int pixelWidth, int pixelHeight)
|
||||
|
||||
void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle commandHandle, float viewMatrix[16], float projectionMatrix[16])
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle command, float viewMatrix[16], float projectionMatrix[16])
|
||||
{
|
||||
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA);
|
||||
for (int i=0;i<16;i++)
|
||||
{
|
||||
command->m_requestPixelDataArguments.m_projectionMatrix[i] = projectionMatrix[i];
|
||||
command->m_requestPixelDataArguments.m_viewMatrix[i] = viewMatrix[i];
|
||||
}
|
||||
command->m_updateFlags |= REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES;
|
||||
}
|
||||
|
||||
void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData)
|
||||
@ -704,6 +710,7 @@ void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImage
|
||||
PhysicsClient* cl = (PhysicsClient* ) physClient;
|
||||
if (cl)
|
||||
{
|
||||
cl->getCachedCameraImage(imageData);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -67,7 +67,6 @@ void b3GetDebugLines(b3PhysicsClientHandle physClient, struct b3DebugLines* l
|
||||
|
||||
///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);
|
||||
|
||||
|
@ -2,7 +2,7 @@
|
||||
#include "PhysicsClientExample.h"
|
||||
|
||||
#include "../CommonInterfaces/CommonMultiBodyBase.h"
|
||||
|
||||
#include "../CommonInterfaces/Common2dCanvasInterface.h"
|
||||
#include "SharedMemoryCommon.h"
|
||||
#include "../CommonInterfaces/CommonParameterInterface.h"
|
||||
#include "PhysicsClientC_API.h"
|
||||
@ -21,6 +21,9 @@ struct MyMotorInfo2
|
||||
int m_qIndex;
|
||||
};
|
||||
|
||||
int camVisualizerWidth = 1024/3;
|
||||
int camVisualizerHeight = 768/3;
|
||||
|
||||
|
||||
#define MAX_NUM_MOTORS 128
|
||||
|
||||
@ -37,6 +40,9 @@ protected:
|
||||
int m_sharedMemoryKey;
|
||||
int m_selectedBody;
|
||||
int m_prevSelectedBody;
|
||||
struct Common2dCanvasInterface* m_canvas;
|
||||
int m_canvasIndex;
|
||||
|
||||
void createButton(const char* name, int id, bool isTrigger );
|
||||
|
||||
void createButtons();
|
||||
@ -240,8 +246,12 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
|
||||
///request an image from a simulated camera, using a software renderer.
|
||||
|
||||
b3SharedMemoryCommandHandle commandHandle = b3InitRequestCameraImage(m_physicsClientHandle);
|
||||
//void b3RequestCameraImageSetResolution(b3SharedMemoryCommandHandle command, int pixelWidth, int pixelHeight);
|
||||
//void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle command, float viewMatrix[16], float projectionMatrix[16]);
|
||||
|
||||
float viewMatrix[16];
|
||||
float projectionMatrix[16];
|
||||
this->m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraProjectionMatrix(projectionMatrix);
|
||||
this->m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraViewMatrix(viewMatrix);
|
||||
b3RequestCameraImageSetCameraMatrices(commandHandle, viewMatrix,projectionMatrix);
|
||||
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
|
||||
break;
|
||||
}
|
||||
@ -401,7 +411,8 @@ m_selectedBody(-1),
|
||||
m_prevSelectedBody(-1),
|
||||
m_numMotors(0),
|
||||
m_options(options),
|
||||
m_isOptionalServerConnected(false)
|
||||
m_isOptionalServerConnected(false),
|
||||
m_canvas(0)
|
||||
{
|
||||
b3Printf("Started PhysicsClientExample\n");
|
||||
}
|
||||
@ -518,6 +529,34 @@ void PhysicsClientExample::initPhysics()
|
||||
|
||||
if (m_options == eCLIENTEXAMPLE_SERVER)
|
||||
{
|
||||
m_canvas = m_guiHelper->get2dCanvasInterface();
|
||||
if (m_canvas)
|
||||
{
|
||||
|
||||
|
||||
m_canvasIndex = m_canvas->createCanvas("Synthetic Camera",camVisualizerWidth, camVisualizerHeight);
|
||||
|
||||
for (int i=0;i<camVisualizerWidth;i++)
|
||||
{
|
||||
for (int j=0;j<camVisualizerHeight;j++)
|
||||
{
|
||||
unsigned char red=255;
|
||||
unsigned char green=255;
|
||||
unsigned char blue=255;
|
||||
unsigned char alpha=255;
|
||||
if (i==j)
|
||||
{
|
||||
red = 0;
|
||||
green=0;
|
||||
blue=0;
|
||||
}
|
||||
m_canvas->setPixel(m_canvasIndex,i,j,red,green,blue,alpha);
|
||||
}
|
||||
}
|
||||
m_canvas->refreshImageData(m_canvasIndex);
|
||||
|
||||
}
|
||||
|
||||
m_isOptionalServerConnected = m_physicsServer.connectSharedMemory( m_guiHelper);
|
||||
}
|
||||
|
||||
@ -564,7 +603,35 @@ void PhysicsClientExample::stepSimulation(float deltaTime)
|
||||
}
|
||||
if (statusType ==CMD_CAMERA_IMAGE_COMPLETED)
|
||||
{
|
||||
b3Printf("Camera image OK\n");
|
||||
static int counter=0;
|
||||
char msg[1024];
|
||||
sprintf(msg,"Camera image %d OK\n",counter++);
|
||||
b3CameraImageData imageData;
|
||||
b3GetCameraImageData(m_physicsClientHandle,&imageData);
|
||||
if (m_canvas && m_canvasIndex >=0)
|
||||
{
|
||||
for (int i=0;i<imageData.m_pixelWidth;i++)
|
||||
{
|
||||
for (int j=0;j<imageData.m_pixelHeight;j++)
|
||||
{
|
||||
int xIndex = int(float(i)*(float(camVisualizerWidth)/float(imageData.m_pixelWidth)));
|
||||
int yIndex = int(float(j)*(float(camVisualizerHeight)/float(imageData.m_pixelHeight)));
|
||||
btClamp(yIndex,0,imageData.m_pixelHeight);
|
||||
btClamp(xIndex,0,imageData.m_pixelWidth);
|
||||
int bytesPerPixel = 4;
|
||||
|
||||
int pixelIndex = (i+j*imageData.m_pixelWidth)*bytesPerPixel;
|
||||
m_canvas->setPixel(m_canvasIndex,xIndex,camVisualizerHeight-1-yIndex,
|
||||
imageData.m_rgbColorData[pixelIndex],
|
||||
imageData.m_rgbColorData[pixelIndex+1],
|
||||
imageData.m_rgbColorData[pixelIndex+2],
|
||||
imageData.m_rgbColorData[pixelIndex+3]);
|
||||
}
|
||||
}
|
||||
m_canvas->refreshImageData(m_canvasIndex);
|
||||
}
|
||||
|
||||
b3Printf(msg);
|
||||
}
|
||||
if (statusType == CMD_CAMERA_IMAGE_FAILED)
|
||||
{
|
||||
|
@ -32,6 +32,11 @@ struct PhysicsClientSharedMemoryInternalData {
|
||||
btAlignedObjectArray<TmpFloat3> m_debugLinesTo;
|
||||
btAlignedObjectArray<TmpFloat3> m_debugLinesColor;
|
||||
|
||||
int m_cachedCameraPixelsWidth;
|
||||
int m_cachedCameraPixelsHeight;
|
||||
btAlignedObjectArray<unsigned char> m_cachedCameraPixelsRGBA;
|
||||
btAlignedObjectArray<float> m_cachedCameraDepthBuffer;
|
||||
|
||||
SharedMemoryStatus m_lastServerStatus;
|
||||
|
||||
int m_counter;
|
||||
@ -46,8 +51,10 @@ struct PhysicsClientSharedMemoryInternalData {
|
||||
: m_sharedMemory(0),
|
||||
m_ownsSharedMemory(false),
|
||||
m_testBlock1(0),
|
||||
m_counter(0),
|
||||
m_serverLoadUrdfOK(false),
|
||||
m_counter(0),
|
||||
m_cachedCameraPixelsWidth(0),
|
||||
m_cachedCameraPixelsHeight(0),
|
||||
m_serverLoadUrdfOK(false),
|
||||
m_isConnected(false),
|
||||
m_waitingForServer(false),
|
||||
m_hasLastServerStatus(false),
|
||||
@ -419,7 +426,30 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
|
||||
|
||||
case CMD_CAMERA_IMAGE_COMPLETED:
|
||||
{
|
||||
b3Printf("Camera image OK\n");
|
||||
if (m_data->m_verboseOutput)
|
||||
{
|
||||
b3Printf("Camera image OK\n");
|
||||
}
|
||||
|
||||
int numBytesPerPixel = 4;//RGBA
|
||||
int numTotalPixels = serverCmd.m_sendPixelDataArguments.m_startingPixelIndex+
|
||||
serverCmd.m_sendPixelDataArguments.m_numPixelsCopied+
|
||||
serverCmd.m_sendPixelDataArguments.m_numRemainingPixels;
|
||||
|
||||
m_data->m_cachedCameraPixelsWidth = 0;
|
||||
m_data->m_cachedCameraPixelsHeight = 0;
|
||||
|
||||
m_data->m_cachedCameraDepthBuffer.resize(numTotalPixels);
|
||||
m_data->m_cachedCameraPixelsRGBA.resize(numTotalPixels*numBytesPerPixel);
|
||||
unsigned char* rgbaPixelsReceived =
|
||||
(unsigned char*)&m_data->m_testBlock1->m_bulletStreamDataServerToClientRefactor[0];
|
||||
|
||||
for (int i=0;i<serverCmd.m_sendPixelDataArguments.m_numPixelsCopied*numBytesPerPixel;i++)
|
||||
{
|
||||
m_data->m_cachedCameraPixelsRGBA[i + serverCmd.m_sendPixelDataArguments.m_startingPixelIndex*numBytesPerPixel]
|
||||
= rgbaPixelsReceived[i];
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
@ -445,6 +475,30 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
|
||||
m_data->m_waitingForServer = false;
|
||||
} else {
|
||||
m_data->m_waitingForServer = true;
|
||||
}
|
||||
|
||||
if (serverCmd.m_type == CMD_CAMERA_IMAGE_COMPLETED)
|
||||
{
|
||||
SharedMemoryCommand& command = m_data->m_testBlock1->m_clientCommands[0];
|
||||
|
||||
if (serverCmd.m_sendPixelDataArguments.m_numRemainingPixels > 0)
|
||||
{
|
||||
|
||||
|
||||
// continue requesting remaining pixels
|
||||
command.m_type = CMD_REQUEST_CAMERA_IMAGE_DATA;
|
||||
command.m_requestPixelDataArguments.m_startPixelIndex =
|
||||
serverCmd.m_sendPixelDataArguments.m_startingPixelIndex +
|
||||
serverCmd.m_sendPixelDataArguments.m_numPixelsCopied;
|
||||
submitClientCommand(command);
|
||||
return 0;
|
||||
} else
|
||||
{
|
||||
m_data->m_cachedCameraPixelsWidth = serverCmd.m_sendPixelDataArguments.m_imageWidth;
|
||||
m_data->m_cachedCameraPixelsHeight = serverCmd.m_sendPixelDataArguments.m_imageHeight;
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
if ((serverCmd.m_type == CMD_DEBUG_LINES_COMPLETED) &&
|
||||
@ -508,6 +562,14 @@ void PhysicsClientSharedMemory::uploadBulletFileToSharedMemory(const char* data,
|
||||
}
|
||||
}
|
||||
|
||||
void PhysicsClientSharedMemory::getCachedCameraImage(struct b3CameraImageData* cameraData)
|
||||
{
|
||||
cameraData->m_pixelWidth = m_data->m_cachedCameraPixelsWidth;
|
||||
cameraData->m_pixelHeight = m_data->m_cachedCameraPixelsHeight;
|
||||
cameraData->m_depthValues = m_data->m_cachedCameraDepthBuffer.size() ? &m_data->m_cachedCameraDepthBuffer[0] : 0;
|
||||
cameraData->m_rgbColorData = m_data->m_cachedCameraPixelsRGBA.size() ? &m_data->m_cachedCameraPixelsRGBA[0] : 0;
|
||||
}
|
||||
|
||||
const float* PhysicsClientSharedMemory::getDebugLinesFrom() const {
|
||||
if (m_data->m_debugLinesFrom.size()) {
|
||||
return &m_data->m_debugLinesFrom[0].m_x;
|
||||
|
@ -45,6 +45,7 @@ public:
|
||||
virtual const float* getDebugLinesFrom() const;
|
||||
virtual const float* getDebugLinesTo() const;
|
||||
virtual const float* getDebugLinesColor() const;
|
||||
virtual void getCachedCameraImage(struct b3CameraImageData* cameraData);
|
||||
};
|
||||
|
||||
#endif // BT_PHYSICS_CLIENT_API_H
|
||||
|
@ -328,3 +328,14 @@ const float* PhysicsDirect::getDebugLinesColor() const
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
void PhysicsDirect::getCachedCameraImage(b3CameraImageData* cameraData)
|
||||
{
|
||||
if (cameraData)
|
||||
{
|
||||
cameraData->m_pixelHeight = 0;
|
||||
cameraData->m_pixelWidth = 0;
|
||||
cameraData->m_depthValues = 0;
|
||||
cameraData->m_rgbColorData = 0;
|
||||
}
|
||||
}
|
||||
|
@ -57,6 +57,8 @@ public:
|
||||
virtual const float* getDebugLinesTo() const;
|
||||
virtual const float* getDebugLinesColor() const;
|
||||
|
||||
virtual void getCachedCameraImage(b3CameraImageData* cameraData);
|
||||
|
||||
};
|
||||
|
||||
#endif //PHYSICS_DIRECT_H
|
||||
|
@ -113,3 +113,8 @@ const float* PhysicsLoopBack::getDebugLinesColor() const
|
||||
{
|
||||
return m_data->m_physicsClient->getDebugLinesColor();
|
||||
}
|
||||
|
||||
void PhysicsLoopBack::getCachedCameraImage(struct b3CameraImageData* cameraData)
|
||||
{
|
||||
return m_data->m_physicsClient->getCachedCameraImage(cameraData);
|
||||
}
|
||||
|
@ -52,6 +52,7 @@ public:
|
||||
virtual const float* getDebugLinesFrom() const;
|
||||
virtual const float* getDebugLinesTo() const;
|
||||
virtual const float* getDebugLinesColor() const;
|
||||
virtual void getCachedCameraImage(struct b3CameraImageData* cameraData);
|
||||
|
||||
};
|
||||
|
||||
|
@ -4,7 +4,7 @@
|
||||
#include "../Importers/ImportURDFDemo/BulletUrdfImporter.h"
|
||||
#include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h"
|
||||
#include "../Importers/ImportURDFDemo/URDF2Bullet.h"
|
||||
#include "../Importers/ImportURDFDemo/DefaultVisualShapeConverter.h"
|
||||
#include "TinyRendererVisualShapeConverter.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h"
|
||||
@ -288,7 +288,6 @@ struct PhysicsServerCommandProcessorInternalData
|
||||
///handle management
|
||||
btAlignedObjectArray<InternalBodyHandle> m_bodyHandles;
|
||||
int m_numUsedHandles; // number of active handles
|
||||
|
||||
int m_firstFreeHandle; // free handles list
|
||||
InternalBodyHandle* getHandle(int handle)
|
||||
{
|
||||
@ -411,6 +410,7 @@ struct PhysicsServerCommandProcessorInternalData
|
||||
btVector3 m_hitPos;
|
||||
btScalar m_oldPickingDist;
|
||||
bool m_prevCanSleep;
|
||||
TinyRendererVisualShapeConverter m_visualConverter;
|
||||
|
||||
PhysicsServerCommandProcessorInternalData()
|
||||
:
|
||||
@ -693,8 +693,8 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto
|
||||
}
|
||||
|
||||
|
||||
DefaultVisualShapeConverter visualConverter(m_data->m_guiHelper);
|
||||
BulletURDFImporter u2b(m_data->m_guiHelper, &visualConverter);
|
||||
|
||||
BulletURDFImporter u2b(m_data->m_guiHelper, &m_data->m_visualConverter);
|
||||
|
||||
|
||||
bool loadOk = u2b.loadURDF(fileName, useFixedBase);
|
||||
@ -967,8 +967,72 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
|
||||
case CMD_REQUEST_CAMERA_IMAGE_DATA:
|
||||
{
|
||||
serverStatusOut.m_type = CMD_CAMERA_IMAGE_COMPLETED;
|
||||
|
||||
int startPixelIndex = clientCmd.m_requestPixelDataArguments.m_startPixelIndex;
|
||||
int width, height;
|
||||
int numPixelsCopied = 0;
|
||||
|
||||
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_USE_HARDWARE_OPENGL)!=0)
|
||||
{
|
||||
m_data->m_guiHelper->copyCameraImageData(0,0,0,0,0,&width,&height,0);
|
||||
}
|
||||
//else
|
||||
{
|
||||
if (clientCmd.m_requestPixelDataArguments.m_startPixelIndex==0)
|
||||
{
|
||||
printf("-------------------------------\nRendering\n");
|
||||
|
||||
|
||||
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES)!=0)
|
||||
{
|
||||
m_data->m_visualConverter.render(
|
||||
clientCmd.m_requestPixelDataArguments.m_viewMatrix,
|
||||
clientCmd.m_requestPixelDataArguments.m_projectionMatrix);
|
||||
} else
|
||||
{
|
||||
m_data->m_visualConverter.render();
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
int numTotalPixels = width*height;
|
||||
int numRemainingPixels = numTotalPixels - startPixelIndex;
|
||||
|
||||
|
||||
if (numRemainingPixels>0)
|
||||
{
|
||||
int maxNumPixels = bufferSizeInBytes/8-1;
|
||||
unsigned char* pixelRGBA = (unsigned char*)bufferServerToClient;
|
||||
int numRequestedPixels = btMin(maxNumPixels,numRemainingPixels);
|
||||
|
||||
float* depthBuffer = (float*)(bufferServerToClient+numRequestedPixels*4);
|
||||
|
||||
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_USE_HARDWARE_OPENGL)!=0)
|
||||
{
|
||||
m_data->m_guiHelper->copyCameraImageData(pixelRGBA,numRequestedPixels,depthBuffer,numRequestedPixels,startPixelIndex,&width,&height,&numPixelsCopied);
|
||||
} else
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
//each pixel takes 4 RGBA values and 1 float = 8 bytes
|
||||
|
||||
} else
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
serverStatusOut.m_type = CMD_CAMERA_IMAGE_COMPLETED;
|
||||
serverStatusOut.m_sendPixelDataArguments.m_numPixelsCopied = numPixelsCopied;
|
||||
serverStatusOut.m_sendPixelDataArguments.m_numRemainingPixels = numRemainingPixels - numPixelsCopied;
|
||||
serverStatusOut.m_sendPixelDataArguments.m_startingPixelIndex = startPixelIndex;
|
||||
serverStatusOut.m_sendPixelDataArguments.m_imageWidth = width;
|
||||
serverStatusOut.m_sendPixelDataArguments.m_imageHeight= height;
|
||||
hasStatus = true;
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
@ -1555,6 +1619,10 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
{
|
||||
m_data->m_guiHelper->getRenderInterface()->removeAllInstances();
|
||||
}
|
||||
if (m_data)
|
||||
{
|
||||
m_data->m_visualConverter.resetAll();
|
||||
}
|
||||
deleteDynamicsWorld();
|
||||
createEmptyDynamicsWorld();
|
||||
m_data->exitHandles();
|
||||
|
@ -113,6 +113,21 @@ struct RequestDebugLinesArgs
|
||||
int m_startingLineIndex;
|
||||
};
|
||||
|
||||
struct RequestPixelDataArgs
|
||||
{
|
||||
float m_viewMatrix[16];
|
||||
float m_projectionMatrix[16];
|
||||
int m_startPixelIndex;
|
||||
};
|
||||
|
||||
enum EnumRequestPixelDataUpdateFlags
|
||||
{
|
||||
REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES=1,
|
||||
REQUEST_PIXEL_ARGS_USE_HARDWARE_OPENGL=2,
|
||||
};
|
||||
|
||||
|
||||
|
||||
struct SendDebugLinesArgs
|
||||
{
|
||||
int m_startingLineIndex;
|
||||
@ -120,6 +135,16 @@ struct SendDebugLinesArgs
|
||||
int m_numRemainingDebugLines;
|
||||
};
|
||||
|
||||
struct SendPixelDataArgs
|
||||
{
|
||||
int m_imageWidth;
|
||||
int m_imageHeight;
|
||||
|
||||
int m_startingPixelIndex;
|
||||
int m_numPixelsCopied;
|
||||
int m_numRemainingPixels;
|
||||
};
|
||||
|
||||
struct PickBodyArgs
|
||||
{
|
||||
double m_rayFromWorld[3];
|
||||
@ -270,6 +295,7 @@ struct SharedMemoryCommand
|
||||
struct CreateSensorArgs m_createSensorArguments;
|
||||
struct CreateBoxShapeArgs m_createBoxShapeArguments;
|
||||
struct RequestDebugLinesArgs m_requestDebugLinesArguments;
|
||||
struct RequestPixelDataArgs m_requestPixelDataArguments;
|
||||
struct PickBodyArgs m_pickBodyArguments;
|
||||
};
|
||||
};
|
||||
@ -291,6 +317,7 @@ struct SharedMemoryStatus
|
||||
struct BulletDataStreamArgs m_dataStreamArguments;
|
||||
struct SendActualStateArgs m_sendActualStateArgs;
|
||||
struct SendDebugLinesArgs m_sendDebugLinesArgs;
|
||||
struct SendPixelDataArgs m_sendPixelDataArguments;
|
||||
struct RigidBodyCreateArgs m_rigidBodyCreateArgs;
|
||||
};
|
||||
};
|
||||
|
@ -12,26 +12,26 @@ subject to the following restrictions:
|
||||
*/
|
||||
|
||||
|
||||
#include "DefaultVisualShapeConverter.h"
|
||||
#include "TinyRendererVisualShapeConverter.h"
|
||||
|
||||
|
||||
|
||||
#include "URDFImporterInterface.h"
|
||||
#include "../Importers/ImportURDFDemo/URDFImporterInterface.h"
|
||||
#include "btBulletCollisionCommon.h"
|
||||
#include "../ImportObjDemo/LoadMeshFromObj.h"
|
||||
#include "../ImportSTLDemo/LoadMeshFromSTL.h"
|
||||
#include "../ImportColladaDemo/LoadMeshFromCollada.h"
|
||||
#include "../Importers/ImportObjDemo/LoadMeshFromObj.h"
|
||||
#include "../Importers/ImportSTLDemo/LoadMeshFromSTL.h"
|
||||
#include "../Importers/ImportColladaDemo/LoadMeshFromCollada.h"
|
||||
#include "BulletCollision/CollisionShapes/btShapeHull.h"//to create a tesselation of a generic btConvexShape
|
||||
#include "../../CommonInterfaces/CommonGUIHelperInterface.h"
|
||||
#include "../CommonInterfaces/CommonGUIHelperInterface.h"
|
||||
#include "Bullet3Common/b3FileUtils.h"
|
||||
#include <string>
|
||||
#include "../../Utils/b3ResourcePath.h"
|
||||
|
||||
|
||||
#include "../Utils/b3ResourcePath.h"
|
||||
#include "../TinyRenderer/TinyRenderer.h"
|
||||
#include "../OpenGLWindow/SimpleCamera.h"
|
||||
|
||||
#include <iostream>
|
||||
#include <fstream>
|
||||
#include "UrdfParser.h"
|
||||
#include "../Importers/ImportURDFDemo/UrdfParser.h"
|
||||
|
||||
|
||||
enum MyFileType
|
||||
@ -41,21 +41,53 @@ enum MyFileType
|
||||
MY_FILE_OBJ=3,
|
||||
};
|
||||
|
||||
|
||||
struct DefaultVisualShapeConverterInternalData
|
||||
struct TinyRendererObjectArray
|
||||
{
|
||||
struct GUIHelperInterface* m_guiHelper;
|
||||
//char m_pathPrefix[1024];
|
||||
btHashMap<btHashInt,btVector4> m_linkColors;
|
||||
btAlignedObjectArray< TinyRenderObjectData*> m_renderObjects;
|
||||
};
|
||||
|
||||
#define START_WIDTH 640
|
||||
#define START_HEIGHT 480
|
||||
|
||||
struct TinyRendererVisualShapeConverterInternalData
|
||||
{
|
||||
|
||||
btHashMap<btHashPtr,TinyRendererObjectArray*> m_swRenderInstances;
|
||||
|
||||
int m_upAxis;
|
||||
int m_swWidth;
|
||||
int m_swHeight;
|
||||
TGAImage m_rgbColorBuffer;
|
||||
b3AlignedObjectArray<float> m_depthBuffer;
|
||||
SimpleCamera m_camera;
|
||||
|
||||
TinyRendererVisualShapeConverterInternalData()
|
||||
:m_upAxis(2),
|
||||
m_swWidth(START_WIDTH),
|
||||
m_swHeight(START_HEIGHT),
|
||||
m_rgbColorBuffer(START_WIDTH,START_HEIGHT,TGAImage::RGB)
|
||||
{
|
||||
m_depthBuffer.resize(m_swWidth*m_swHeight);
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
|
||||
DefaultVisualShapeConverter::DefaultVisualShapeConverter(struct GUIHelperInterface* guiHelper)
|
||||
|
||||
TinyRendererVisualShapeConverter::TinyRendererVisualShapeConverter()
|
||||
{
|
||||
m_data = new DefaultVisualShapeConverterInternalData();
|
||||
m_data->m_guiHelper = guiHelper;
|
||||
m_data = new TinyRendererVisualShapeConverterInternalData();
|
||||
|
||||
float dist = 1.5;
|
||||
float pitch = -80;
|
||||
float yaw = 10;
|
||||
float targetPos[3]={0,0,0};
|
||||
m_data->m_camera.setCameraUpAxis(m_data->m_upAxis);
|
||||
resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
||||
|
||||
|
||||
}
|
||||
DefaultVisualShapeConverter::~DefaultVisualShapeConverter()
|
||||
TinyRendererVisualShapeConverter::~TinyRendererVisualShapeConverter()
|
||||
{
|
||||
delete m_data;
|
||||
}
|
||||
@ -385,8 +417,9 @@ void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPref
|
||||
|
||||
|
||||
|
||||
int DefaultVisualShapeConverter::convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfModel& model, class btCollisionShape* colShape)
|
||||
void TinyRendererVisualShapeConverter::convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfModel& model, class btCollisionObject* colObj)
|
||||
{
|
||||
|
||||
btAlignedObjectArray<GLInstanceVertex> vertices;
|
||||
btAlignedObjectArray<int> indices;
|
||||
btTransform startTrans; startTrans.setIdentity();
|
||||
@ -408,29 +441,147 @@ int DefaultVisualShapeConverter::convertVisualShapes(int linkIndex, const char*
|
||||
{
|
||||
UrdfMaterial *const mat = *matPtr;
|
||||
//printf("UrdfMaterial %s, rgba = %f,%f,%f,%f\n",mat->m_name.c_str(),mat->m_rgbaColor[0],mat->m_rgbaColor[1],mat->m_rgbaColor[2],mat->m_rgbaColor[3]);
|
||||
m_data->m_linkColors.insert(linkIndex,mat->m_rgbaColor);
|
||||
//m_data->m_linkColors.insert(linkIndex,mat->m_rgbaColor);
|
||||
}
|
||||
|
||||
TinyRendererObjectArray** visualsPtr = m_data->m_swRenderInstances[colObj];
|
||||
if (visualsPtr==0)
|
||||
{
|
||||
m_data->m_swRenderInstances.insert(colObj,new TinyRendererObjectArray);
|
||||
}
|
||||
visualsPtr = m_data->m_swRenderInstances[colObj];
|
||||
btAssert(visualsPtr);
|
||||
TinyRendererObjectArray* visuals = *visualsPtr;
|
||||
|
||||
convertURDFToVisualShape(&vis, pathPrefix, localInertiaFrame.inverse()*childTrans, vertices, indices);
|
||||
|
||||
|
||||
if (vertices.size() && indices.size())
|
||||
{
|
||||
TinyRenderObjectData* tinyObj = new TinyRenderObjectData(m_data->m_swWidth,m_data->m_swHeight,m_data->m_rgbColorBuffer,m_data->m_depthBuffer);
|
||||
tinyObj->registerMeshShape(&vertices[0].xyzw[0],vertices.size(),&indices[0],indices.size());
|
||||
visuals->m_renderObjects.push_back(tinyObj);
|
||||
}
|
||||
}
|
||||
}
|
||||
if (vertices.size() && indices.size())
|
||||
{
|
||||
graphicsIndex = m_data->m_guiHelper->registerGraphicsShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size());
|
||||
}
|
||||
return graphicsIndex;
|
||||
}
|
||||
|
||||
bool DefaultVisualShapeConverter::getLinkColor(int linkIndex, btVector4& colorRGBA) const
|
||||
void TinyRendererVisualShapeConverter::setUpAxis(int axis)
|
||||
{
|
||||
const btVector4* rgbaPtr = m_data->m_linkColors[linkIndex];
|
||||
if (rgbaPtr)
|
||||
{
|
||||
colorRGBA = *rgbaPtr;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
m_data->m_upAxis = axis;
|
||||
m_data->m_camera.setCameraUpAxis(axis);
|
||||
m_data->m_camera.update();
|
||||
}
|
||||
void TinyRendererVisualShapeConverter::resetCamera(float camDist, float pitch, float yaw, float camPosX,float camPosY, float camPosZ)
|
||||
{
|
||||
m_data->m_camera.setCameraDistance(camDist);
|
||||
m_data->m_camera.setCameraPitch(pitch);
|
||||
m_data->m_camera.setCameraYaw(yaw);
|
||||
m_data->m_camera.setCameraTargetPosition(camPosX,camPosY,camPosZ);
|
||||
m_data->m_camera.setAspectRatio((float)m_data->m_swWidth/(float)m_data->m_swHeight);
|
||||
m_data->m_camera.update();
|
||||
|
||||
}
|
||||
|
||||
void TinyRendererVisualShapeConverter::clearBuffers(TGAColor& clearColor)
|
||||
{
|
||||
for(int y=0;y<m_data->m_swHeight;++y)
|
||||
{
|
||||
for(int x=0;x<m_data->m_swWidth;++x)
|
||||
{
|
||||
m_data->m_rgbColorBuffer.set(x,y,clearColor);
|
||||
m_data->m_depthBuffer[x+y*m_data->m_swWidth] = -1e30f;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void TinyRendererVisualShapeConverter::render()
|
||||
{
|
||||
|
||||
ATTRIBUTE_ALIGNED16(float viewMat[16]);
|
||||
ATTRIBUTE_ALIGNED16(float projMat[16]);
|
||||
|
||||
m_data->m_camera.getCameraProjectionMatrix(projMat);
|
||||
m_data->m_camera.getCameraViewMatrix(viewMat);
|
||||
|
||||
render(viewMat,projMat);
|
||||
}
|
||||
|
||||
void TinyRendererVisualShapeConverter::render(const float viewMat[16], const float projMat[16])
|
||||
{
|
||||
//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(btScalar modelMat[16]);
|
||||
|
||||
|
||||
btVector3 lightDirWorld(-5,200,-40);
|
||||
switch (m_data->m_upAxis)
|
||||
{
|
||||
case 1:
|
||||
lightDirWorld = btVector3(-50.f,100,30);
|
||||
break;
|
||||
case 2:
|
||||
lightDirWorld = btVector3(-50.f,30,100);
|
||||
break;
|
||||
default:{}
|
||||
};
|
||||
|
||||
lightDirWorld.normalize();
|
||||
|
||||
printf("num m_swRenderInstances = %d\n", m_data->m_swRenderInstances.size());
|
||||
for (int i=0;i<m_data->m_swRenderInstances.size();i++)
|
||||
{
|
||||
TinyRendererObjectArray** visualArrayPtr = m_data->m_swRenderInstances.getAtIndex(i);
|
||||
if (0==visualArrayPtr)
|
||||
continue;//can this ever happen?
|
||||
TinyRendererObjectArray* visualArray = *visualArrayPtr;
|
||||
|
||||
btHashPtr colObjHash = m_data->m_swRenderInstances.getKeyAtIndex(i);
|
||||
|
||||
|
||||
const btCollisionObject* colObj = (btCollisionObject*) colObjHash.getPointer();
|
||||
|
||||
for (int v=0;v<visualArray->m_renderObjects.size();v++)
|
||||
{
|
||||
|
||||
TinyRenderObjectData* renderObj = visualArray->m_renderObjects[v];
|
||||
|
||||
|
||||
//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);
|
||||
}
|
||||
}
|
||||
//printf("write tga \n");
|
||||
m_data->m_rgbColorBuffer.write_tga_file("camera.tga");
|
||||
|
||||
}
|
||||
|
||||
void TinyRendererVisualShapeConverter::resetAll()
|
||||
{
|
||||
//todo: free memory
|
||||
m_data->m_swRenderInstances.clear();
|
||||
}
|
||||
|
34
examples/SharedMemory/TinyRendererVisualShapeConverter.h
Normal file
34
examples/SharedMemory/TinyRendererVisualShapeConverter.h
Normal file
@ -0,0 +1,34 @@
|
||||
#ifndef TINY_RENDERER_VISUAL_SHAPE_CONVERTER_H
|
||||
#define TINY_RENDERER_VISUAL_SHAPE_CONVERTER_H
|
||||
|
||||
|
||||
#include "../Importers/ImportURDFDemo/LinkVisualShapesConverter.h"
|
||||
|
||||
struct TinyRendererVisualShapeConverter : public LinkVisualShapesConverter
|
||||
{
|
||||
|
||||
struct TinyRendererVisualShapeConverterInternalData* m_data;
|
||||
|
||||
TinyRendererVisualShapeConverter();
|
||||
|
||||
virtual ~TinyRendererVisualShapeConverter();
|
||||
|
||||
virtual void convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfModel& model, class btCollisionObject* colShape);
|
||||
|
||||
void setUpAxis(int axis);
|
||||
|
||||
void resetCamera(float camDist, float pitch, float yaw, float camPosX,float camPosY, float camPosZ);
|
||||
|
||||
void clearBuffers(struct TGAColor& clearColor);
|
||||
|
||||
void resetAll();
|
||||
|
||||
void render();
|
||||
void render(const float viewMat[16], const float projMat[16]);
|
||||
|
||||
};
|
||||
|
||||
|
||||
|
||||
|
||||
#endif //TINY_RENDERER_VISUAL_SHAPE_CONVERTER_H
|
@ -40,14 +40,21 @@ files {
|
||||
"PhysicsLoopBackC_API.h",
|
||||
"PhysicsServerCommandProcessor.cpp",
|
||||
"PhysicsServerCommandProcessor.h",
|
||||
"TinyRendererVisualShapeConverter.cpp",
|
||||
"TinyRendererVisualShapeConverter.h",
|
||||
"../TinyRenderer/geometry.cpp",
|
||||
"../TinyRenderer/model.cpp",
|
||||
"../TinyRenderer/tgaimage.cpp",
|
||||
"../TinyRenderer/our_gl.cpp",
|
||||
"../TinyRenderer/TinyRenderer.cpp",
|
||||
"../OpenGLWindow/SimpleCamera.cpp",
|
||||
"../OpenGLWindow/SimpleCamera.h",
|
||||
"../Importers/ImportURDFDemo/ConvertRigidBodies2MultiBody.h",
|
||||
"../Importers/ImportURDFDemo/MultiBodyCreationInterface.h",
|
||||
"../Importers/ImportURDFDemo/MyMultiBodyCreator.cpp",
|
||||
"../Importers/ImportURDFDemo/MyMultiBodyCreator.h",
|
||||
"../Importers/ImportURDFDemo/BulletUrdfImporter.cpp",
|
||||
"../Importers/ImportURDFDemo/BulletUrdfImporter.h",
|
||||
"../Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp",
|
||||
"../Importers/ImportURDFDemo/DefaultVisualShapeConverter.h",
|
||||
"../Importers/ImportURDFDemo/UrdfParser.cpp",
|
||||
"../Importers/ImportURDFDemo/urdfStringSplit.cpp",
|
||||
"../Importers/ImportURDFDemo/UrdfParser.cpp",
|
||||
|
@ -316,6 +316,17 @@ struct TinyRendererGUIHelper : public GUIHelperInterface
|
||||
|
||||
}
|
||||
|
||||
virtual void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int* width, int* height, int* numPixelsCopied)
|
||||
{
|
||||
if (width)
|
||||
*width = 0;
|
||||
if (height)
|
||||
*height = 0;
|
||||
if (numPixelsCopied)
|
||||
*numPixelsCopied = 0;
|
||||
}
|
||||
|
||||
|
||||
virtual void autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld)
|
||||
{
|
||||
|
||||
|
@ -12,7 +12,7 @@
|
||||
#include "../OpenGLWindow/ShapeData.h"
|
||||
#include "LinearMath/btAlignedObjectArray.h"
|
||||
#include "LinearMath/btVector3.h"
|
||||
Vec3f light_dir_world(0,0,0);
|
||||
|
||||
|
||||
|
||||
struct Shader : public IShader {
|
||||
@ -20,9 +20,12 @@ struct Shader : public IShader {
|
||||
Model* m_model;
|
||||
Vec3f m_light_dir_local;
|
||||
Matrix& m_modelMat;
|
||||
Matrix m_invModelMat;
|
||||
|
||||
Matrix& m_modelView1;
|
||||
Matrix& m_projectionMatrix;
|
||||
Vec3f m_localScaling;
|
||||
//Vec3f m_localNormal;
|
||||
|
||||
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
|
||||
@ -37,7 +40,7 @@ struct Shader : public IShader {
|
||||
m_modelMat(modelMat),
|
||||
m_localScaling(localScaling)
|
||||
{
|
||||
|
||||
m_invModelMat = m_modelMat.invert_transpose();
|
||||
}
|
||||
|
||||
virtual Vec4f vertex(int iface, int nthvert) {
|
||||
@ -47,10 +50,15 @@ struct Shader : public IShader {
|
||||
varying_uv.set_col(nthvert, uv);
|
||||
|
||||
//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_invModelMat*embed<4>(m_model->normal(iface, nthvert), 0.f)));
|
||||
//m_localNormal = m_model->normal(iface, nthvert);
|
||||
//varying_nrm.set_col(nthvert, m_model->normal(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);
|
||||
|
||||
Vec4f gl_Vertex = m_projectionMatrix*m_modelView1*embed<4>(scaledVert);
|
||||
|
||||
varying_tri.set_col(nthvert, gl_Vertex);
|
||||
//ndc_tri.set_col(nthvert, proj<3>(gl_Vertex/gl_Vertex[3]));
|
||||
@ -63,7 +71,8 @@ struct Shader : public IShader {
|
||||
|
||||
//float diff = 1;//full-bright
|
||||
float ambient = 0.7;
|
||||
float diff = ambient+b3Min(b3Max(0.f, bn*light_dir_world),(1-ambient));
|
||||
//float diff = ambient+b3Min(b3Max(0.f, bn*light_dir_world),(1-ambient));
|
||||
float diff = ambient+b3Min(b3Max(0.f, bn*m_light_dir_local),(1-ambient));
|
||||
//float diff = b3Max(0.f, n*m_light_dir_local);
|
||||
color = m_model->diffuse(uv)*diff;
|
||||
|
||||
@ -222,7 +231,7 @@ TinyRenderObjectData::~TinyRenderObjectData()
|
||||
|
||||
void TinyRenderer::renderObject(TinyRenderObjectData& renderData)
|
||||
{
|
||||
light_dir_world = Vec3f(renderData.m_lightDirWorld[0],renderData.m_lightDirWorld[1],renderData.m_lightDirWorld[2]);
|
||||
Vec3f light_dir_local = Vec3f(renderData.m_lightDirWorld[0],renderData.m_lightDirWorld[1],renderData.m_lightDirWorld[2]);
|
||||
Model* model = renderData.m_model;
|
||||
if (0==model)
|
||||
return;
|
||||
@ -236,22 +245,20 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData)
|
||||
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;
|
||||
|
||||
Vec3f light_dir_local = proj<3>((renderData.m_projectionMatrix*renderData.m_viewMatrix*renderData.m_modelMatrix*embed<4>(light_dir_world, 0.f))).normalize();
|
||||
|
||||
|
||||
{
|
||||
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);
|
||||
|
||||
|
||||
|
||||
for (int i=0; i<model->nfaces(); i++) {
|
||||
printf("Render %d triangles.\n",model->nfaces());
|
||||
for (int i=0; i<model->nfaces(); i++)
|
||||
{
|
||||
|
||||
for (int j=0; j<3; j++) {
|
||||
shader.vertex(i, j);
|
||||
|
@ -395,6 +395,19 @@ protected:
|
||||
return &m_valueArray[index];
|
||||
}
|
||||
|
||||
Key getKeyAtIndex(int index)
|
||||
{
|
||||
btAssert(index < m_keyArray.size());
|
||||
return m_keyArray[index];
|
||||
}
|
||||
|
||||
const Key getKeyAtIndex(int index) const
|
||||
{
|
||||
btAssert(index < m_keyArray.size());
|
||||
return m_keyArray[index];
|
||||
}
|
||||
|
||||
|
||||
Value* operator[](const Key& key) {
|
||||
return find(key);
|
||||
}
|
||||
|
@ -73,8 +73,6 @@
|
||||
"../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.h",
|
||||
"../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp",
|
||||
"../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.h",
|
||||
"../../examples/Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp",
|
||||
"../../examples/Importers/ImportURDFDemo/DefaultVisualShapeConverter.h",
|
||||
"../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp",
|
||||
"../../examples/Importers/ImportURDFDemo/UrdfParser.cpp",
|
||||
"../../examples/Importers/ImportURDFDemo/UrdfParser.h",
|
||||
|
@ -48,6 +48,15 @@ ENDIF()
|
||||
../../examples/SharedMemory/PosixSharedMemory.h
|
||||
../../examples/Utils/b3ResourcePath.cpp
|
||||
../../examples/Utils/b3ResourcePath.h
|
||||
../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp
|
||||
../../examples/SharedMemory/TinyRendererVisualShapeConverter.h
|
||||
../../examples/OpenGLWindow/SimpleCamera.cpp
|
||||
../../examples/OpenGLWindow/SimpleCamera.h
|
||||
../../examples/TinyRenderer/geometry.cpp
|
||||
../../examples/TinyRenderer/model.cpp
|
||||
../../examples/TinyRenderer/tgaimage.cpp
|
||||
../../examples/TinyRenderer/our_gl.cpp
|
||||
../../examples/TinyRenderer/TinyRenderer.cpp
|
||||
../../examples/ThirdPartyLibs/tinyxml/tinystr.cpp
|
||||
../../examples/ThirdPartyLibs/tinyxml/tinyxml.cpp
|
||||
../../examples/ThirdPartyLibs/tinyxml/tinyxmlerror.cpp
|
||||
@ -62,7 +71,7 @@ ENDIF()
|
||||
../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp
|
||||
../../examples/Importers/ImportURDFDemo/UrdfParser.cpp
|
||||
../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp
|
||||
../../examples/Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp
|
||||
|
||||
|
||||
)
|
||||
|
||||
|
@ -66,6 +66,15 @@ project ("Test_PhysicsServerLoopBack")
|
||||
"../../examples/SharedMemory/Win32SharedMemory.h",
|
||||
"../../examples/SharedMemory/PosixSharedMemory.cpp",
|
||||
"../../examples/SharedMemory/PosixSharedMemory.h",
|
||||
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp",
|
||||
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.h",
|
||||
"../../examples/OpenGLWindow/SimpleCamera.cpp",
|
||||
"../../examples/OpenGLWindow/SimpleCamera.h",
|
||||
"../../examples/TinyRenderer/geometry.cpp",
|
||||
"../../examples/TinyRenderer/model.cpp",
|
||||
"../../examples/TinyRenderer/tgaimage.cpp",
|
||||
"../../examples/TinyRenderer/our_gl.cpp",
|
||||
"../../examples/TinyRenderer/TinyRenderer.cpp",
|
||||
"../../examples/Utils/b3ResourcePath.cpp",
|
||||
"../../examples/Utils/b3ResourcePath.h",
|
||||
"../../examples/ThirdPartyLibs/tinyxml/tinystr.cpp",
|
||||
@ -78,7 +87,6 @@ project ("Test_PhysicsServerLoopBack")
|
||||
"../../examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp",
|
||||
"../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp",
|
||||
"../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp",
|
||||
"../../examples/Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp",
|
||||
"../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp",
|
||||
"../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp",
|
||||
"../../examples/Importers/ImportURDFDemo/UrdfParser.cpp",
|
||||
@ -124,6 +132,15 @@ project ("Test_PhysicsServerLoopBack")
|
||||
"../../examples/SharedMemory/Win32SharedMemory.h",
|
||||
"../../examples/SharedMemory/PosixSharedMemory.cpp",
|
||||
"../../examples/SharedMemory/PosixSharedMemory.h",
|
||||
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp",
|
||||
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.h",
|
||||
"../../examples/TinyRenderer/geometry.cpp",
|
||||
"../../examples/TinyRenderer/model.cpp",
|
||||
"../../examples/TinyRenderer/tgaimage.cpp",
|
||||
"../../examples/TinyRenderer/our_gl.cpp",
|
||||
"../../examples/TinyRenderer/TinyRenderer.cpp",
|
||||
"../../examples/OpenGLWindow/SimpleCamera.cpp",
|
||||
"../../examples/OpenGLWindow/SimpleCamera.h",
|
||||
"../../examples/Utils/b3ResourcePath.cpp",
|
||||
"../../examples/Utils/b3ResourcePath.h",
|
||||
"../../examples/ThirdPartyLibs/tinyxml/tinystr.cpp",
|
||||
@ -136,7 +153,6 @@ project ("Test_PhysicsServerLoopBack")
|
||||
"../../examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp",
|
||||
"../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp",
|
||||
"../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp",
|
||||
"../../examples/Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp",
|
||||
"../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp",
|
||||
"../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp",
|
||||
"../../examples/Importers/ImportURDFDemo/UrdfParser.cpp",
|
||||
@ -214,6 +230,13 @@ project ("Test_PhysicsServerInProcessExampleBrowser")
|
||||
"../../examples/SharedMemory/Win32SharedMemory.h",
|
||||
"../../examples/SharedMemory/PosixSharedMemory.cpp",
|
||||
"../../examples/SharedMemory/PosixSharedMemory.h",
|
||||
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp",
|
||||
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.h",
|
||||
"../../examples/TinyRenderer/geometry.cpp",
|
||||
"../../examples/TinyRenderer/model.cpp",
|
||||
"../../examples/TinyRenderer/tgaimage.cpp",
|
||||
"../../examples/TinyRenderer/our_gl.cpp",
|
||||
"../../examples/TinyRenderer/TinyRenderer.cpp",
|
||||
"../../examples/Utils/b3ResourcePath.cpp",
|
||||
"../../examples/Utils/b3ResourcePath.h",
|
||||
"../../examples/ThirdPartyLibs/tinyxml/tinystr.cpp",
|
||||
@ -226,7 +249,6 @@ project ("Test_PhysicsServerInProcessExampleBrowser")
|
||||
"../../examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp",
|
||||
"../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp",
|
||||
"../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp",
|
||||
"../../examples/Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp",
|
||||
"../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp",
|
||||
"../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp",
|
||||
"../../examples/Importers/ImportURDFDemo/UrdfParser.cpp",
|
||||
|
Loading…
Reference in New Issue
Block a user