PyBullet: move TinyRenderer into a plugin, default statically loaded. You can also dynamically load a render plugin, as shown in renderPlugin.py example. premake has a way to compile the tinyRendererPlugin.
This commit is contained in:
@@ -10,8 +10,8 @@ INCLUDE_DIRECTORIES(
|
||||
SET(BulletRobotics_SRCS
|
||||
../../examples/SharedMemory/IKTrajectoryHelper.cpp
|
||||
../../examples/SharedMemory/IKTrajectoryHelper.h
|
||||
../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp
|
||||
../../examples/SharedMemory/TinyRendererVisualShapeConverter.h
|
||||
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp
|
||||
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp
|
||||
../../examples/OpenGLWindow/SimpleCamera.cpp
|
||||
../../examples/OpenGLWindow/SimpleCamera.h
|
||||
../../examples/TinyRenderer/geometry.cpp
|
||||
|
||||
@@ -143,11 +143,10 @@ SET(BulletExampleBrowser_SRCS
|
||||
../TinyRenderer/tgaimage.cpp
|
||||
../TinyRenderer/our_gl.cpp
|
||||
../TinyRenderer/TinyRenderer.cpp
|
||||
../SharedMemory/TinyRendererVisualShapeConverter.cpp
|
||||
../SharedMemory/TinyRendererVisualShapeConverter.h
|
||||
../SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp
|
||||
../SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp
|
||||
../SharedMemory/IKTrajectoryHelper.cpp
|
||||
../SharedMemory/IKTrajectoryHelper.h
|
||||
|
||||
../SharedMemory/PhysicsServer.cpp
|
||||
../SharedMemory/PhysicsClientSharedMemory.cpp
|
||||
../SharedMemory/PhysicsClientSharedMemory_C_API.cpp
|
||||
|
||||
@@ -110,8 +110,8 @@ project "App_BulletExampleBrowser"
|
||||
"../SharedMemory/PhysicsServerCommandProcessor.cpp",
|
||||
"../SharedMemory/PhysicsServerCommandProcessor.h",
|
||||
"../SharedMemory/b3PluginManager.cpp",
|
||||
"../SharedMemory/TinyRendererVisualShapeConverter.cpp",
|
||||
"../SharedMemory/TinyRendererVisualShapeConverter.h",
|
||||
"../SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp",
|
||||
"../SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp",
|
||||
"../SharedMemory/SharedMemoryCommands.h",
|
||||
"../SharedMemory/SharedMemoryPublic.h",
|
||||
"../MultiThreading/MultiThreadingExample.cpp",
|
||||
|
||||
@@ -184,7 +184,7 @@ struct MyMJCFDefaults
|
||||
struct BulletMJCFImporterInternalData
|
||||
{
|
||||
GUIHelperInterface* m_guiHelper;
|
||||
struct LinkVisualShapesConverter* m_customVisualShapesConverter;
|
||||
struct UrdfRenderingInterface* m_customVisualShapesConverter;
|
||||
char m_pathPrefix[1024];
|
||||
|
||||
std::string m_sourceFileName; // with path
|
||||
@@ -1419,7 +1419,7 @@ struct BulletMJCFImporterInternalData
|
||||
|
||||
};
|
||||
|
||||
BulletMJCFImporter::BulletMJCFImporter(struct GUIHelperInterface* helper, LinkVisualShapesConverter* customConverter, int flags)
|
||||
BulletMJCFImporter::BulletMJCFImporter(struct GUIHelperInterface* helper, UrdfRenderingInterface* customConverter, int flags)
|
||||
{
|
||||
m_data = new BulletMJCFImporterInternalData();
|
||||
m_data->m_guiHelper = helper;
|
||||
|
||||
@@ -2,7 +2,7 @@
|
||||
#define BULLET_MJCF_IMPORTER_H
|
||||
|
||||
#include "../ImportURDFDemo/URDFImporterInterface.h"
|
||||
#include "../ImportURDFDemo/LinkVisualShapesConverter.h"
|
||||
#include "../ImportURDFDemo/UrdfRenderingInterface.h"
|
||||
|
||||
|
||||
struct MJCFErrorLogger
|
||||
@@ -27,7 +27,7 @@ class BulletMJCFImporter : public URDFImporterInterface
|
||||
void convertURDFToVisualShapeInternal(const struct UrdfVisual* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray<struct GLInstanceVertex>& verticesOut, btAlignedObjectArray<int>& indicesOut, btAlignedObjectArray<MJCFURDFTexture>& texturesOut) const;
|
||||
|
||||
public:
|
||||
BulletMJCFImporter(struct GUIHelperInterface* helper, LinkVisualShapesConverter* customConverter, int flags);
|
||||
BulletMJCFImporter(struct GUIHelperInterface* helper, UrdfRenderingInterface* customConverter, int flags);
|
||||
virtual ~BulletMJCFImporter();
|
||||
|
||||
virtual bool parseMJCFString(const char* xmlString, MJCFErrorLogger* logger);
|
||||
|
||||
@@ -51,7 +51,7 @@ ATTRIBUTE_ALIGNED16(struct) BulletURDFInternalData
|
||||
mutable btAlignedObjectArray<btTriangleMesh*> m_allocatedMeshInterfaces;
|
||||
btHashMap<btHashPtr, UrdfCollision> m_bulletCollisionShape2UrdfCollision;
|
||||
|
||||
LinkVisualShapesConverter* m_customVisualShapesConverter;
|
||||
UrdfRenderingInterface* m_customVisualShapesConverter;
|
||||
bool m_enableTinyRenderer;
|
||||
int m_flags;
|
||||
|
||||
@@ -82,7 +82,7 @@ void BulletURDFImporter::printTree()
|
||||
// btAssert(0);
|
||||
}
|
||||
|
||||
BulletURDFImporter::BulletURDFImporter(struct GUIHelperInterface* helper, LinkVisualShapesConverter* customConverter, double globalScaling, int flags)
|
||||
BulletURDFImporter::BulletURDFImporter(struct GUIHelperInterface* helper, UrdfRenderingInterface* customConverter, double globalScaling, int flags)
|
||||
{
|
||||
m_data = new BulletURDFInternalData;
|
||||
m_data->setGlobalScaling(globalScaling);
|
||||
|
||||
@@ -3,7 +3,7 @@
|
||||
|
||||
#include "URDFImporterInterface.h"
|
||||
|
||||
#include "LinkVisualShapesConverter.h"
|
||||
#include "UrdfRenderingInterface.h"
|
||||
|
||||
struct BulletURDFTexture
|
||||
{
|
||||
@@ -23,7 +23,7 @@ class BulletURDFImporter : public URDFImporterInterface
|
||||
|
||||
public:
|
||||
|
||||
BulletURDFImporter(struct GUIHelperInterface* helper, LinkVisualShapesConverter* customConverter, double globalScaling=1, int flags=0);
|
||||
BulletURDFImporter(struct GUIHelperInterface* helper, UrdfRenderingInterface* customConverter, double globalScaling=1, int flags=0);
|
||||
|
||||
virtual ~BulletURDFImporter();
|
||||
|
||||
|
||||
@@ -4,7 +4,6 @@
|
||||
#include <string>
|
||||
|
||||
|
||||
|
||||
///See audio_source element in http://sdformat.org/spec?ver=1.6&elem=link
|
||||
struct SDFAudioSource
|
||||
{
|
||||
|
||||
@@ -1,6 +1,7 @@
|
||||
#ifndef URDF_JOINT_TYPES_H
|
||||
#define URDF_JOINT_TYPES_H
|
||||
|
||||
#include "LinearMath/btScalar.h"
|
||||
|
||||
enum UrdfJointTypes
|
||||
{
|
||||
@@ -11,7 +12,6 @@ enum UrdfJointTypes
|
||||
URDFPlanarJoint,
|
||||
URDFFixedJoint,
|
||||
};
|
||||
#include "LinearMath/btScalar.h"
|
||||
|
||||
enum URDF_LinkContactFlags
|
||||
{
|
||||
|
||||
@@ -6,9 +6,9 @@
|
||||
#include "LinearMath/btHashMap.h"
|
||||
#include "URDFJointTypes.h"
|
||||
#include "SDFAudioTypes.h"
|
||||
#include <string>
|
||||
|
||||
#define btArray btAlignedObjectArray
|
||||
#include <string>
|
||||
|
||||
struct ErrorLogger
|
||||
{
|
||||
|
||||
@@ -1,12 +1,12 @@
|
||||
#ifndef LINK_VISUAL_SHAPES_CONVERTER_H
|
||||
#define LINK_VISUAL_SHAPES_CONVERTER_H
|
||||
#ifndef URDF_RENDERING_INTERFACE_H
|
||||
#define URDF_RENDERING_INTERFACE_H
|
||||
|
||||
struct UrdfLink;
|
||||
struct UrdfModel;
|
||||
class btTransform;
|
||||
class btCollisionObject;
|
||||
|
||||
struct LinkVisualShapesConverter
|
||||
|
||||
struct UrdfRenderingInterface
|
||||
{
|
||||
virtual void convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfLink* linkPtr, const UrdfModel* model, int shapeUid, int objectIndex) =0;
|
||||
|
||||
@@ -17,8 +17,8 @@ SET(RobotSimulator_SRCS
|
||||
../../examples/SharedMemory/IKTrajectoryHelper.cpp
|
||||
../../examples/SharedMemory/IKTrajectoryHelper.h
|
||||
../../examples/ExampleBrowser/InProcessExampleBrowser.cpp
|
||||
../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp
|
||||
../../examples/SharedMemory/TinyRendererVisualShapeConverter.h
|
||||
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp
|
||||
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp
|
||||
../../examples/OpenGLWindow/SimpleCamera.cpp
|
||||
../../examples/OpenGLWindow/SimpleCamera.h
|
||||
../../examples/TinyRenderer/geometry.cpp
|
||||
|
||||
@@ -32,8 +32,8 @@ myfiles =
|
||||
"../../examples/SharedMemory/Win32SharedMemory.h",
|
||||
"../../examples/SharedMemory/PosixSharedMemory.cpp",
|
||||
"../../examples/SharedMemory/PosixSharedMemory.h",
|
||||
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp",
|
||||
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.h",
|
||||
"../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp",
|
||||
"../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp",
|
||||
"../../examples/TinyRenderer/geometry.cpp",
|
||||
"../../examples/TinyRenderer/model.cpp",
|
||||
"../../examples/TinyRenderer/tgaimage.cpp",
|
||||
|
||||
@@ -36,9 +36,9 @@ SET(SharedMemory_SRCS
|
||||
SharedMemoryCommandProcessor.h
|
||||
PhysicsServerCommandProcessor.cpp
|
||||
PhysicsServerCommandProcessor.h
|
||||
TinyRendererVisualShapeConverter.cpp
|
||||
TinyRendererVisualShapeConverter.h
|
||||
SharedMemoryCommands.h
|
||||
plugins/tinyRendererPlugin/tinyRendererPlugin.cpp
|
||||
plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp
|
||||
SharedMemoryCommands.h
|
||||
SharedMemoryPublic.h
|
||||
b3PluginManager.cpp
|
||||
../TinyRenderer/geometry.cpp
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
#include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h"
|
||||
#include "../Importers/ImportURDFDemo/URDF2Bullet.h"
|
||||
#include "../Extras/InverseDynamics/btMultiBodyTreeCreator.hpp"
|
||||
#include "TinyRendererVisualShapeConverter.h"
|
||||
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h"
|
||||
@@ -47,6 +47,12 @@
|
||||
#include "plugins/vrSyncPlugin/vrSyncPlugin.h"
|
||||
#endif
|
||||
|
||||
|
||||
#ifndef SKIP_STATIC_TINYRENDERER_PLUGIN
|
||||
#include "plugins/tinyRendererPlugin/tinyRendererPlugin.h"
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef B3_ENABLE_TINY_AUDIO
|
||||
#include "../TinyAudio/b3SoundEngine.h"
|
||||
#endif
|
||||
@@ -1564,8 +1570,7 @@ struct PhysicsServerCommandProcessorInternalData
|
||||
btVector3 m_hitPos;
|
||||
btScalar m_oldPickingDist;
|
||||
bool m_prevCanSleep;
|
||||
TinyRendererVisualShapeConverter m_tempVisualConverter;//we may move this into a plugin
|
||||
LinkVisualShapesConverter* m_visualConverterPtr;
|
||||
|
||||
#ifdef B3_ENABLE_TINY_AUDIO
|
||||
b3SoundEngine m_soundEngine;
|
||||
#endif
|
||||
@@ -1599,14 +1604,16 @@ struct PhysicsServerCommandProcessorInternalData
|
||||
m_pickingMultiBodyPoint2Point(0)
|
||||
{
|
||||
|
||||
m_visualConverterPtr=&m_tempVisualConverter;
|
||||
|
||||
{
|
||||
//register static plugins:
|
||||
#ifdef STATIC_LINK_VR_PLUGIN
|
||||
m_pluginManager.registerStaticLinkedPlugin("vrSyncPlugin", initPlugin_vrSyncPlugin, exitPlugin_vrSyncPlugin, executePluginCommand_vrSyncPlugin,preTickPluginCallback_vrSyncPlugin,0);
|
||||
m_pluginManager.registerStaticLinkedPlugin("vrSyncPlugin", initPlugin_vrSyncPlugin, exitPlugin_vrSyncPlugin, executePluginCommand_vrSyncPlugin,preTickPluginCallback_vrSyncPlugin,0,0);
|
||||
#endif //STATIC_LINK_VR_PLUGIN
|
||||
|
||||
#ifndef SKIP_STATIC_TINYRENDERER_PLUGIN
|
||||
int renderPluginId = m_pluginManager.registerStaticLinkedPlugin("tinyRendererPlugin", initPlugin_tinyRendererPlugin, exitPlugin_tinyRendererPlugin, executePluginCommand_tinyRendererPlugin,0,0,getRenderInterface_tinyRendererPlugin);
|
||||
m_pluginManager.selectPluginRenderer(renderPluginId);
|
||||
#endif
|
||||
}
|
||||
|
||||
m_vrControllerEvents.init();
|
||||
@@ -2121,9 +2128,9 @@ struct ProgrammaticUrdfInterface : public URDFImporterInterface
|
||||
//UrdfVisual vis;
|
||||
//link.m_visualArray.push_back(vis);
|
||||
//UrdfLink*const* linkPtr = model.m_links.getAtIndex(urdfIndex);
|
||||
if (m_data->m_visualConverterPtr)
|
||||
if (m_data->m_pluginManager.getRenderInterface())
|
||||
{
|
||||
m_data->m_visualConverterPtr->convertVisualShapes(linkIndex,pathPrefix,localInertiaFrame, &link, &model, colObj->getBroadphaseHandle()->getUid(), bodyUniqueId);
|
||||
m_data->m_pluginManager.getRenderInterface()->convertVisualShapes(linkIndex,pathPrefix,localInertiaFrame, &link, &model, colObj->getBroadphaseHandle()->getUid(), bodyUniqueId);
|
||||
}
|
||||
}
|
||||
virtual void setBodyUniqueId(int bodyId)
|
||||
@@ -2708,7 +2715,7 @@ bool PhysicsServerCommandProcessor::loadMjcf(const char* fileName, char* bufferS
|
||||
|
||||
m_data->m_sdfRecentLoadedBodies.clear();
|
||||
|
||||
BulletMJCFImporter u2b(m_data->m_guiHelper, m_data->m_visualConverterPtr, flags);
|
||||
BulletMJCFImporter u2b(m_data->m_guiHelper, m_data->m_pluginManager.getRenderInterface(), flags);
|
||||
|
||||
bool useFixedBase = false;
|
||||
MyMJCFLogger2 logger;
|
||||
@@ -2731,7 +2738,7 @@ bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferSe
|
||||
|
||||
m_data->m_sdfRecentLoadedBodies.clear();
|
||||
|
||||
BulletURDFImporter u2b(m_data->m_guiHelper, m_data->m_visualConverterPtr, globalScaling, flags);
|
||||
BulletURDFImporter u2b(m_data->m_guiHelper, m_data->m_pluginManager.getRenderInterface(), globalScaling, flags);
|
||||
u2b.setEnableTinyRenderer(m_data->m_enableTinyRenderer);
|
||||
|
||||
bool forceFixedBase = false;
|
||||
@@ -2763,7 +2770,7 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto
|
||||
|
||||
|
||||
|
||||
BulletURDFImporter u2b(m_data->m_guiHelper, m_data->m_visualConverterPtr, globalScaling, flags);
|
||||
BulletURDFImporter u2b(m_data->m_guiHelper, m_data->m_pluginManager.getRenderInterface(), globalScaling, flags);
|
||||
u2b.setEnableTinyRenderer(m_data->m_enableTinyRenderer);
|
||||
bool loadOk = u2b.loadURDF(fileName, useFixedBase);
|
||||
|
||||
@@ -3080,9 +3087,9 @@ bool PhysicsServerCommandProcessor::processRequestCameraImageCommand(const struc
|
||||
if ((clientCmd.m_requestPixelDataArguments.m_startPixelIndex==0) &&
|
||||
(clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT)!=0)
|
||||
{
|
||||
if (m_data->m_visualConverterPtr)
|
||||
if (m_data->m_pluginManager.getRenderInterface())
|
||||
{
|
||||
m_data->m_visualConverterPtr->setWidthAndHeight(clientCmd.m_requestPixelDataArguments.m_pixelWidth,
|
||||
m_data->m_pluginManager.getRenderInterface()->setWidthAndHeight(clientCmd.m_requestPixelDataArguments.m_pixelWidth,
|
||||
clientCmd.m_requestPixelDataArguments.m_pixelHeight);
|
||||
}
|
||||
}
|
||||
@@ -3091,9 +3098,9 @@ bool PhysicsServerCommandProcessor::processRequestCameraImageCommand(const struc
|
||||
{
|
||||
flags = clientCmd.m_requestPixelDataArguments.m_flags;
|
||||
}
|
||||
if (m_data->m_visualConverterPtr)
|
||||
if (m_data->m_pluginManager.getRenderInterface())
|
||||
{
|
||||
m_data->m_visualConverterPtr->setFlags(flags);
|
||||
m_data->m_pluginManager.getRenderInterface()->setFlags(flags);
|
||||
}
|
||||
|
||||
int numTotalPixels = width*height;
|
||||
@@ -3168,7 +3175,7 @@ bool PhysicsServerCommandProcessor::processRequestCameraImageCommand(const struc
|
||||
}
|
||||
if (!handled)
|
||||
{
|
||||
if (m_data->m_visualConverterPtr)
|
||||
if (m_data->m_pluginManager.getRenderInterface())
|
||||
{
|
||||
if (clientCmd.m_requestPixelDataArguments.m_startPixelIndex==0)
|
||||
{
|
||||
@@ -3176,48 +3183,48 @@ bool PhysicsServerCommandProcessor::processRequestCameraImageCommand(const struc
|
||||
|
||||
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_LIGHT_DIRECTION) != 0)
|
||||
{
|
||||
m_data->m_visualConverterPtr->setLightDirection(clientCmd.m_requestPixelDataArguments.m_lightDirection[0], clientCmd.m_requestPixelDataArguments.m_lightDirection[1], clientCmd.m_requestPixelDataArguments.m_lightDirection[2]);
|
||||
m_data->m_pluginManager.getRenderInterface()->setLightDirection(clientCmd.m_requestPixelDataArguments.m_lightDirection[0], clientCmd.m_requestPixelDataArguments.m_lightDirection[1], clientCmd.m_requestPixelDataArguments.m_lightDirection[2]);
|
||||
}
|
||||
|
||||
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_LIGHT_COLOR) != 0)
|
||||
{
|
||||
m_data->m_visualConverterPtr->setLightColor(clientCmd.m_requestPixelDataArguments.m_lightColor[0], clientCmd.m_requestPixelDataArguments.m_lightColor[1], clientCmd.m_requestPixelDataArguments.m_lightColor[2]);
|
||||
m_data->m_pluginManager.getRenderInterface()->setLightColor(clientCmd.m_requestPixelDataArguments.m_lightColor[0], clientCmd.m_requestPixelDataArguments.m_lightColor[1], clientCmd.m_requestPixelDataArguments.m_lightColor[2]);
|
||||
}
|
||||
|
||||
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_LIGHT_DISTANCE) != 0)
|
||||
{
|
||||
m_data->m_visualConverterPtr->setLightDistance(clientCmd.m_requestPixelDataArguments.m_lightDistance);
|
||||
m_data->m_pluginManager.getRenderInterface()->setLightDistance(clientCmd.m_requestPixelDataArguments.m_lightDistance);
|
||||
}
|
||||
|
||||
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_SHADOW) != 0)
|
||||
{
|
||||
m_data->m_visualConverterPtr->setShadow((clientCmd.m_requestPixelDataArguments.m_hasShadow!=0));
|
||||
m_data->m_pluginManager.getRenderInterface()->setShadow((clientCmd.m_requestPixelDataArguments.m_hasShadow!=0));
|
||||
}
|
||||
|
||||
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_AMBIENT_COEFF) != 0)
|
||||
{
|
||||
m_data->m_visualConverterPtr->setLightAmbientCoeff(clientCmd.m_requestPixelDataArguments.m_lightAmbientCoeff);
|
||||
m_data->m_pluginManager.getRenderInterface()->setLightAmbientCoeff(clientCmd.m_requestPixelDataArguments.m_lightAmbientCoeff);
|
||||
}
|
||||
|
||||
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_DIFFUSE_COEFF) != 0)
|
||||
{
|
||||
m_data->m_visualConverterPtr->setLightDiffuseCoeff(clientCmd.m_requestPixelDataArguments.m_lightDiffuseCoeff);
|
||||
m_data->m_pluginManager.getRenderInterface()->setLightDiffuseCoeff(clientCmd.m_requestPixelDataArguments.m_lightDiffuseCoeff);
|
||||
}
|
||||
|
||||
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_SPECULAR_COEFF) != 0)
|
||||
{
|
||||
m_data->m_visualConverterPtr->setLightSpecularCoeff(clientCmd.m_requestPixelDataArguments.m_lightSpecularCoeff);
|
||||
m_data->m_pluginManager.getRenderInterface()->setLightSpecularCoeff(clientCmd.m_requestPixelDataArguments.m_lightSpecularCoeff);
|
||||
}
|
||||
|
||||
for (int i=0;i<m_data->m_dynamicsWorld->getNumCollisionObjects();i++)
|
||||
{
|
||||
const btCollisionObject* colObj = m_data->m_dynamicsWorld->getCollisionObjectArray()[i];
|
||||
m_data->m_visualConverterPtr->syncTransform(colObj->getBroadphaseHandle()->getUid(),colObj->getWorldTransform(),colObj->getCollisionShape()->getLocalScaling());
|
||||
m_data->m_pluginManager.getRenderInterface()->syncTransform(colObj->getBroadphaseHandle()->getUid(),colObj->getWorldTransform(),colObj->getCollisionShape()->getLocalScaling());
|
||||
}
|
||||
|
||||
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES)!=0)
|
||||
{
|
||||
m_data->m_visualConverterPtr->render(
|
||||
m_data->m_pluginManager.getRenderInterface()->render(
|
||||
clientCmd.m_requestPixelDataArguments.m_viewMatrix,
|
||||
clientCmd.m_requestPixelDataArguments.m_projectionMatrix);
|
||||
} else
|
||||
@@ -3238,18 +3245,18 @@ bool PhysicsServerCommandProcessor::processRequestCameraImageCommand(const struc
|
||||
tmpCamResult.m_target);
|
||||
if (result)
|
||||
{
|
||||
m_data->m_visualConverterPtr->render(tmpCamResult.m_viewMatrix,tmpCamResult.m_projectionMatrix);
|
||||
m_data->m_pluginManager.getRenderInterface()->render(tmpCamResult.m_viewMatrix,tmpCamResult.m_projectionMatrix);
|
||||
} else
|
||||
{
|
||||
m_data->m_visualConverterPtr->render();
|
||||
m_data->m_pluginManager.getRenderInterface()->render();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (m_data->m_visualConverterPtr)
|
||||
if (m_data->m_pluginManager.getRenderInterface())
|
||||
{
|
||||
m_data->m_visualConverterPtr->copyCameraImageData(pixelRGBA,numRequestedPixels,
|
||||
m_data->m_pluginManager.getRenderInterface()->copyCameraImageData(pixelRGBA,numRequestedPixels,
|
||||
depthBuffer,numRequestedPixels,
|
||||
segmentationMaskBuffer, numRequestedPixels,
|
||||
startPixelIndex,&width,&height,&numPixelsCopied);
|
||||
@@ -3889,7 +3896,7 @@ bool PhysicsServerCommandProcessor::processCreateVisualShapeCommand(const struct
|
||||
serverStatusOut.m_type = CMD_CREATE_VISUAL_SHAPE_FAILED;
|
||||
double globalScaling = 1.f;
|
||||
int flags=0;
|
||||
BulletURDFImporter u2b(m_data->m_guiHelper, m_data->m_visualConverterPtr, globalScaling, flags);
|
||||
BulletURDFImporter u2b(m_data->m_guiHelper, m_data->m_pluginManager.getRenderInterface(), globalScaling, flags);
|
||||
u2b.setEnableTinyRenderer(m_data->m_enableTinyRenderer);
|
||||
btTransform localInertiaFrame;
|
||||
localInertiaFrame.setIdentity();
|
||||
@@ -6525,7 +6532,7 @@ bool PhysicsServerCommandProcessor::processSendPhysicsParametersCommand(const st
|
||||
}
|
||||
if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_DETERMINISTIC_OVERLAPPING_PAIRS)
|
||||
{
|
||||
m_data->m_dynamicsWorld->getDispatchInfo().m_deterministicOverlappingPairs = clientCmd.m_physSimParamArgs.m_deterministicOverlappingPairs;
|
||||
m_data->m_dynamicsWorld->getDispatchInfo().m_deterministicOverlappingPairs = (clientCmd.m_physSimParamArgs.m_deterministicOverlappingPairs!=0);
|
||||
}
|
||||
if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_DELTA_TIME)
|
||||
{
|
||||
@@ -7450,9 +7457,9 @@ bool PhysicsServerCommandProcessor::processRemoveBodyCommand(const struct Shared
|
||||
|
||||
if (bodyHandle->m_multiBody->getBaseCollider())
|
||||
{
|
||||
if (m_data->m_visualConverterPtr)
|
||||
if (m_data->m_pluginManager.getRenderInterface())
|
||||
{
|
||||
m_data->m_visualConverterPtr->removeVisualShape(bodyHandle->m_multiBody->getBaseCollider()->getBroadphaseHandle()->getUid());
|
||||
m_data->m_pluginManager.getRenderInterface()->removeVisualShape(bodyHandle->m_multiBody->getBaseCollider()->getBroadphaseHandle()->getUid());
|
||||
}
|
||||
m_data->m_dynamicsWorld->removeCollisionObject(bodyHandle->m_multiBody->getBaseCollider());
|
||||
int graphicsIndex = bodyHandle->m_multiBody->getBaseCollider()->getUserIndex();
|
||||
@@ -7463,9 +7470,9 @@ bool PhysicsServerCommandProcessor::processRemoveBodyCommand(const struct Shared
|
||||
|
||||
if (bodyHandle->m_multiBody->getLink(link).m_collider)
|
||||
{
|
||||
if (m_data->m_visualConverterPtr)
|
||||
if (m_data->m_pluginManager.getRenderInterface())
|
||||
{
|
||||
m_data->m_visualConverterPtr->removeVisualShape(bodyHandle->m_multiBody->getLink(link).m_collider->getBroadphaseHandle()->getUid());
|
||||
m_data->m_pluginManager.getRenderInterface()->removeVisualShape(bodyHandle->m_multiBody->getLink(link).m_collider->getBroadphaseHandle()->getUid());
|
||||
}
|
||||
m_data->m_dynamicsWorld->removeCollisionObject(bodyHandle->m_multiBody->getLink(link).m_collider);
|
||||
int graphicsIndex = bodyHandle->m_multiBody->getLink(link).m_collider->getUserIndex();
|
||||
@@ -7483,9 +7490,9 @@ bool PhysicsServerCommandProcessor::processRemoveBodyCommand(const struct Shared
|
||||
}
|
||||
if (bodyHandle->m_rigidBody)
|
||||
{
|
||||
if (m_data->m_visualConverterPtr)
|
||||
if (m_data->m_pluginManager.getRenderInterface())
|
||||
{
|
||||
m_data->m_visualConverterPtr->removeVisualShape(bodyHandle->m_rigidBody->getBroadphaseHandle()->getUid());
|
||||
m_data->m_pluginManager.getRenderInterface()->removeVisualShape(bodyHandle->m_rigidBody->getBroadphaseHandle()->getUid());
|
||||
}
|
||||
serverCmd.m_removeObjectArgs.m_bodyUniqueIds[serverCmd.m_removeObjectArgs.m_numBodies++] = bodyUniqueId;
|
||||
|
||||
@@ -8401,9 +8408,9 @@ bool PhysicsServerCommandProcessor::processRequestVisualShapeInfoCommand(const s
|
||||
serverCmd.m_type = CMD_VISUAL_SHAPE_INFO_FAILED;
|
||||
//retrieve the visual shape information for a specific body
|
||||
|
||||
if (m_data->m_visualConverterPtr)
|
||||
if (m_data->m_pluginManager.getRenderInterface())
|
||||
{
|
||||
int totalNumVisualShapes = m_data->m_visualConverterPtr->getNumVisualShapes(clientCmd.m_requestVisualShapeDataArguments.m_bodyUniqueId);
|
||||
int totalNumVisualShapes = m_data->m_pluginManager.getRenderInterface()->getNumVisualShapes(clientCmd.m_requestVisualShapeDataArguments.m_bodyUniqueId);
|
||||
//int totalBytesPerVisualShape = sizeof (b3VisualShapeData);
|
||||
//int visualShapeStorage = bufferSizeInBytes / totalBytesPerVisualShape - 1;
|
||||
b3VisualShapeData* visualShapeStoragePtr = (b3VisualShapeData*)bufferServerToClient;
|
||||
@@ -8411,7 +8418,7 @@ bool PhysicsServerCommandProcessor::processRequestVisualShapeInfoCommand(const s
|
||||
int remain = totalNumVisualShapes - clientCmd.m_requestVisualShapeDataArguments.m_startingVisualShapeIndex;
|
||||
int shapeIndex = clientCmd.m_requestVisualShapeDataArguments.m_startingVisualShapeIndex;
|
||||
|
||||
int success = m_data->m_visualConverterPtr->getVisualShapesData(clientCmd.m_requestVisualShapeDataArguments.m_bodyUniqueId,
|
||||
int success = m_data->m_pluginManager.getRenderInterface()->getVisualShapesData(clientCmd.m_requestVisualShapeDataArguments.m_bodyUniqueId,
|
||||
shapeIndex,
|
||||
visualShapeStoragePtr);
|
||||
if (success) {
|
||||
@@ -8444,9 +8451,9 @@ bool PhysicsServerCommandProcessor::processUpdateVisualShapeCommand(const struct
|
||||
{
|
||||
if (texHandle)
|
||||
{
|
||||
if (m_data->m_visualConverterPtr)
|
||||
if (m_data->m_pluginManager.getRenderInterface())
|
||||
{
|
||||
m_data->m_visualConverterPtr->activateShapeTexture(clientCmd.m_updateVisualShapeDataArguments.m_bodyUniqueId, clientCmd.m_updateVisualShapeDataArguments.m_jointIndex, clientCmd.m_updateVisualShapeDataArguments.m_shapeIndex, texHandle->m_tinyRendererTextureId);
|
||||
m_data->m_pluginManager.getRenderInterface()->activateShapeTexture(clientCmd.m_updateVisualShapeDataArguments.m_bodyUniqueId, clientCmd.m_updateVisualShapeDataArguments.m_jointIndex, clientCmd.m_updateVisualShapeDataArguments.m_shapeIndex, texHandle->m_tinyRendererTextureId);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -8476,9 +8483,9 @@ bool PhysicsServerCommandProcessor::processUpdateVisualShapeCommand(const struct
|
||||
}
|
||||
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR)
|
||||
{
|
||||
if (m_data->m_visualConverterPtr)
|
||||
if (m_data->m_pluginManager.getRenderInterface())
|
||||
{
|
||||
m_data->m_visualConverterPtr->changeRGBAColor(bodyUniqueId,linkIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
|
||||
m_data->m_pluginManager.getRenderInterface()->changeRGBAColor(bodyUniqueId,linkIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
|
||||
}
|
||||
m_data->m_guiHelper->changeRGBAColor(graphicsIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
|
||||
}
|
||||
@@ -8505,9 +8512,9 @@ bool PhysicsServerCommandProcessor::processUpdateVisualShapeCommand(const struct
|
||||
}
|
||||
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR)
|
||||
{
|
||||
if (m_data->m_visualConverterPtr)
|
||||
if (m_data->m_pluginManager.getRenderInterface())
|
||||
{
|
||||
m_data->m_visualConverterPtr->changeRGBAColor(bodyUniqueId,linkIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
|
||||
m_data->m_pluginManager.getRenderInterface()->changeRGBAColor(bodyUniqueId,linkIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
|
||||
}
|
||||
m_data->m_guiHelper->changeRGBAColor(graphicsIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
|
||||
}
|
||||
@@ -8534,9 +8541,9 @@ bool PhysicsServerCommandProcessor::processUpdateVisualShapeCommand(const struct
|
||||
}
|
||||
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR)
|
||||
{
|
||||
if (m_data->m_visualConverterPtr)
|
||||
if (m_data->m_pluginManager.getRenderInterface())
|
||||
{
|
||||
m_data->m_visualConverterPtr->changeRGBAColor(bodyUniqueId,linkIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
|
||||
m_data->m_pluginManager.getRenderInterface()->changeRGBAColor(bodyUniqueId,linkIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
|
||||
}
|
||||
m_data->m_guiHelper->changeRGBAColor(graphicsIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
|
||||
}
|
||||
@@ -8595,9 +8602,9 @@ bool PhysicsServerCommandProcessor::processLoadTextureCommand(const struct Share
|
||||
texH->m_openglTextureId = -1;
|
||||
|
||||
int uid = -1;
|
||||
if (m_data->m_visualConverterPtr)
|
||||
if (m_data->m_pluginManager.getRenderInterface())
|
||||
{
|
||||
m_data->m_visualConverterPtr->loadTextureFile(relativeFileName);
|
||||
m_data->m_pluginManager.getRenderInterface()->loadTextureFile(relativeFileName);
|
||||
}
|
||||
if(uid>=0)
|
||||
{
|
||||
@@ -9567,9 +9574,9 @@ void PhysicsServerCommandProcessor::resetSimulation()
|
||||
}
|
||||
if (m_data)
|
||||
{
|
||||
if (m_data->m_visualConverterPtr)
|
||||
if (m_data->m_pluginManager.getRenderInterface())
|
||||
{
|
||||
m_data->m_visualConverterPtr->resetAll();
|
||||
m_data->m_pluginManager.getRenderInterface()->resetAll();
|
||||
}
|
||||
for (int i = 0; i < m_data->m_savedStates.size(); i++)
|
||||
{
|
||||
|
||||
@@ -39,8 +39,10 @@ struct b3Plugin
|
||||
PFN_TICK m_preTickFunc;
|
||||
PFN_TICK m_postTickFunc;
|
||||
|
||||
PFN_GET_RENDER_INTERFACE m_getRendererFunc;
|
||||
|
||||
void* m_userPointer;
|
||||
|
||||
|
||||
b3Plugin()
|
||||
:m_pluginHandle(0),
|
||||
m_ownsPluginHandle(false),
|
||||
@@ -50,6 +52,7 @@ struct b3Plugin
|
||||
m_executeCommandFunc(0),
|
||||
m_preTickFunc(0),
|
||||
m_postTickFunc(0),
|
||||
m_getRendererFunc(0),
|
||||
m_userPointer(0)
|
||||
{
|
||||
}
|
||||
@@ -66,6 +69,7 @@ struct b3Plugin
|
||||
m_preTickFunc = 0;
|
||||
m_postTickFunc = 0;
|
||||
m_userPointer = 0;
|
||||
m_getRendererFunc = 0;
|
||||
}
|
||||
};
|
||||
|
||||
@@ -79,6 +83,12 @@ struct b3PluginManagerInternalData
|
||||
b3AlignedObjectArray<b3KeyboardEvent> m_keyEvents;
|
||||
b3AlignedObjectArray<b3VRControllerEvent> m_vrEvents;
|
||||
b3AlignedObjectArray<b3MouseEvent> m_mouseEvents;
|
||||
int m_activeRendererPluginUid;
|
||||
|
||||
b3PluginManagerInternalData()
|
||||
:m_activeRendererPluginUid(-1)
|
||||
{
|
||||
}
|
||||
};
|
||||
|
||||
b3PluginManager::b3PluginManager(class PhysicsCommandProcessorInterface* physSdk)
|
||||
@@ -151,12 +161,14 @@ int b3PluginManager::loadPlugin(const char* pluginPath, const char* postFixStr)
|
||||
std::string executePluginCommandStr = std::string("executePluginCommand") + postFix;
|
||||
std::string preTickPluginCallbackStr = std::string("preTickPluginCallback") + postFix;
|
||||
std::string postTickPluginCallback = std::string("postTickPluginCallback") + postFix;
|
||||
|
||||
std::string getRendererStr = std::string("getRenderInterface") + postFix;
|
||||
|
||||
plugin->m_initFunc = (PFN_INIT)B3_DYNLIB_IMPORT(pluginHandle, initStr.c_str());
|
||||
plugin->m_exitFunc = (PFN_EXIT)B3_DYNLIB_IMPORT(pluginHandle, exitStr.c_str());
|
||||
plugin->m_executeCommandFunc = (PFN_EXECUTE)B3_DYNLIB_IMPORT(pluginHandle, executePluginCommandStr.c_str());
|
||||
plugin->m_preTickFunc = (PFN_TICK)B3_DYNLIB_IMPORT(pluginHandle, preTickPluginCallbackStr.c_str());
|
||||
plugin->m_postTickFunc = (PFN_TICK)B3_DYNLIB_IMPORT(pluginHandle, postTickPluginCallback.c_str());
|
||||
plugin->m_getRendererFunc = (PFN_GET_RENDER_INTERFACE)B3_DYNLIB_IMPORT(pluginHandle, getRendererStr.c_str());
|
||||
|
||||
if (plugin->m_initFunc && plugin->m_exitFunc && plugin->m_executeCommandFunc)
|
||||
{
|
||||
@@ -201,6 +213,17 @@ int b3PluginManager::loadPlugin(const char* pluginPath, const char* postFixStr)
|
||||
pluginUniqueId = -1;
|
||||
}
|
||||
}
|
||||
|
||||
//for now, automatically select the loaded plugin as active renderer. If wanted, we can add some 'select' mechanism.
|
||||
if (pluginUniqueId>=0)
|
||||
{
|
||||
b3PluginHandle* plugin = m_data->m_plugins.getHandle(pluginUniqueId);
|
||||
if (plugin && plugin->m_getRendererFunc)
|
||||
{
|
||||
selectPluginRenderer(pluginUniqueId);
|
||||
}
|
||||
}
|
||||
|
||||
return pluginUniqueId;
|
||||
}
|
||||
|
||||
@@ -275,11 +298,10 @@ int b3PluginManager::executePluginCommand(int pluginUniqueId, const b3PluginArgu
|
||||
}
|
||||
|
||||
|
||||
int b3PluginManager::registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT initFunc,PFN_EXIT exitFunc, PFN_EXECUTE executeCommandFunc, PFN_TICK preTickFunc, PFN_TICK postTickFunc)
|
||||
int b3PluginManager::registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT initFunc,PFN_EXIT exitFunc, PFN_EXECUTE executeCommandFunc, PFN_TICK preTickFunc, PFN_TICK postTickFunc, PFN_GET_RENDER_INTERFACE getRendererFunc)
|
||||
{
|
||||
|
||||
b3Plugin orgPlugin;
|
||||
|
||||
|
||||
int pluginUniqueId = m_data->m_plugins.allocHandle();
|
||||
b3PluginHandle* pluginHandle = m_data->m_plugins.getHandle(pluginUniqueId);
|
||||
@@ -291,10 +313,12 @@ int b3PluginManager::registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT
|
||||
pluginHandle->m_initFunc = initFunc;
|
||||
pluginHandle->m_preTickFunc = preTickFunc;
|
||||
pluginHandle->m_postTickFunc = postTickFunc;
|
||||
pluginHandle->m_getRendererFunc = getRendererFunc;
|
||||
pluginHandle->m_pluginHandle = 0;
|
||||
pluginHandle->m_pluginPath = pluginPath;
|
||||
pluginHandle->m_userPointer = 0;
|
||||
|
||||
|
||||
m_data->m_pluginMap.insert(pluginPath, pluginHandle);
|
||||
|
||||
{
|
||||
@@ -313,3 +337,34 @@ int b3PluginManager::registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT
|
||||
}
|
||||
return pluginUniqueId;
|
||||
}
|
||||
|
||||
void b3PluginManager::selectPluginRenderer(int pluginUniqueId)
|
||||
{
|
||||
m_data->m_activeRendererPluginUid = pluginUniqueId;
|
||||
}
|
||||
|
||||
UrdfRenderingInterface* b3PluginManager::getRenderInterface()
|
||||
{
|
||||
UrdfRenderingInterface* renderer = 0;
|
||||
|
||||
if (m_data->m_activeRendererPluginUid>=0)
|
||||
{
|
||||
b3PluginHandle* plugin = m_data->m_plugins.getHandle(m_data->m_activeRendererPluginUid);
|
||||
if (plugin)
|
||||
{
|
||||
b3PluginContext context;
|
||||
context.m_userPointer = plugin->m_userPointer;
|
||||
context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect;
|
||||
context.m_numMouseEvents = 0;
|
||||
context.m_mouseEvents = 0;
|
||||
context.m_numKeyEvents = 0;
|
||||
context.m_keyEvents = 0;
|
||||
context.m_numVRControllerEvents = 0;
|
||||
context.m_vrControllerEvents = 0;
|
||||
|
||||
renderer = plugin->m_getRendererFunc(&context);
|
||||
}
|
||||
}
|
||||
return renderer;
|
||||
}
|
||||
|
||||
|
||||
@@ -17,11 +17,13 @@ class b3PluginManager
|
||||
int executePluginCommand(int pluginUniqueId, const struct b3PluginArguments* arguments);
|
||||
void addEvents(const struct b3VRControllerEvent* vrControllerEvents, int numVRControllerEvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents, const struct b3MouseEvent* mouseEvents, int numMouseEvents);
|
||||
void clearEvents();
|
||||
|
||||
|
||||
void tickPlugins(double timeStep, bool isPreTick);
|
||||
|
||||
int registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT initFunc,PFN_EXIT exitFunc, PFN_EXECUTE executeCommandFunc, PFN_TICK preTickFunc, PFN_TICK postTickFunc);
|
||||
|
||||
int registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT initFunc,PFN_EXIT exitFunc, PFN_EXECUTE executeCommandFunc, PFN_TICK preTickFunc, PFN_TICK postTickFunc, PFN_GET_RENDER_INTERFACE getRendererFunc);
|
||||
|
||||
void selectPluginRenderer(int pluginUniqueId);
|
||||
UrdfRenderingInterface* getRenderInterface();
|
||||
};
|
||||
|
||||
#endif //B3_PLUGIN_MANAGER_H
|
||||
|
||||
@@ -30,6 +30,10 @@ extern "C" {
|
||||
typedef B3_API_ENTRY void (B3_API_CALL * PFN_EXIT)(struct b3PluginContext* context);
|
||||
typedef B3_API_ENTRY int (B3_API_CALL * PFN_EXECUTE)(struct b3PluginContext* context, const struct b3PluginArguments* arguments);
|
||||
typedef B3_API_ENTRY int (B3_API_CALL * PFN_TICK)(struct b3PluginContext* context);
|
||||
|
||||
typedef B3_API_ENTRY struct UrdfRenderingInterface* (B3_API_CALL * PFN_GET_RENDER_INTERFACE)(struct b3PluginContext* context);
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
@@ -9,7 +9,7 @@ struct b3PluginContext
|
||||
|
||||
//plugin can modify the m_userPointer to store persistent object pointer (class or struct instance etc)
|
||||
void* m_userPointer;
|
||||
|
||||
|
||||
const struct b3VRControllerEvent* m_vrControllerEvents;
|
||||
int m_numVRControllerEvents;
|
||||
const struct b3KeyboardEvent* m_keyEvents;
|
||||
|
||||
@@ -13,10 +13,10 @@ B3_SHARED_API int initPlugin(struct b3PluginContext* context);
|
||||
B3_SHARED_API void exitPlugin(struct b3PluginContext* context);
|
||||
B3_SHARED_API int executePluginCommand(struct b3PluginContext* context, const struct b3PluginArguments* arguments);
|
||||
|
||||
//preTickPluginCallback and postTickPluginCallback are optional.
|
||||
//all the APIs below are optional
|
||||
B3_SHARED_API int preTickPluginCallback(struct b3PluginContext* context);
|
||||
B3_SHARED_API int postTickPluginCallback(struct b3PluginContext* context);
|
||||
|
||||
B3_SHARED_API struct UrdfRenderingInterface* getRenderInterface(struct b3PluginContext* context);
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
|
||||
@@ -1,13 +1,9 @@
|
||||
#ifndef TINY_RENDERER_VISUAL_SHAPE_CONVERTER_H
|
||||
#define TINY_RENDERER_VISUAL_SHAPE_CONVERTER_H
|
||||
|
||||
#include "../../../Importers/ImportURDFDemo/UrdfRenderingInterface.h"
|
||||
|
||||
#include "../Importers/ImportURDFDemo/LinkVisualShapesConverter.h"
|
||||
|
||||
|
||||
|
||||
|
||||
struct TinyRendererVisualShapeConverter : public LinkVisualShapesConverter
|
||||
struct TinyRendererVisualShapeConverter : public UrdfRenderingInterface
|
||||
{
|
||||
|
||||
struct TinyRendererVisualShapeConverterInternalData* m_data;
|
||||
@@ -28,32 +24,32 @@ struct TinyRendererVisualShapeConverter : public LinkVisualShapesConverter
|
||||
|
||||
virtual void setUpAxis(int axis);
|
||||
|
||||
virtual void resetCamera(float camDist, float yaw, float pitch, float camPosX,float camPosY, float camPosZ);
|
||||
virtual void resetCamera(float camDist, float yaw, float pitch, float camPosX,float camPosY, float camPosZ);
|
||||
|
||||
virtual void clearBuffers(struct TGAColor& clearColor);
|
||||
virtual void clearBuffers(struct TGAColor& clearColor);
|
||||
|
||||
virtual void resetAll();
|
||||
|
||||
virtual void getWidthAndHeight(int& width, int& height);
|
||||
virtual void getWidthAndHeight(int& width, int& height);
|
||||
virtual void setWidthAndHeight(int width, int height);
|
||||
virtual void setLightDirection(float x, float y, float z);
|
||||
virtual void setLightColor(float x, float y, float z);
|
||||
virtual void setLightDistance(float dist);
|
||||
virtual void setLightAmbientCoeff(float ambientCoeff);
|
||||
virtual void setLightDiffuseCoeff(float diffuseCoeff);
|
||||
virtual void setLightSpecularCoeff(float specularCoeff);
|
||||
virtual void setShadow(bool hasShadow);
|
||||
virtual void setLightColor(float x, float y, float z);
|
||||
virtual void setLightDistance(float dist);
|
||||
virtual void setLightAmbientCoeff(float ambientCoeff);
|
||||
virtual void setLightDiffuseCoeff(float diffuseCoeff);
|
||||
virtual void setLightSpecularCoeff(float specularCoeff);
|
||||
virtual void setShadow(bool hasShadow);
|
||||
virtual void setFlags(int flags);
|
||||
|
||||
virtual void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels,int* segmentationMaskBuffer, int segmentationMaskSizeInPixels, int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied);
|
||||
virtual void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels,int* segmentationMaskBuffer, int segmentationMaskSizeInPixels, int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied);
|
||||
|
||||
virtual void render();
|
||||
virtual void render(const float viewMat[16], const float projMat[16]);
|
||||
|
||||
virtual int loadTextureFile(const char* filename);
|
||||
virtual int registerTexture(unsigned char* texels, int width, int height);
|
||||
virtual int loadTextureFile(const char* filename);
|
||||
virtual int registerTexture(unsigned char* texels, int width, int height);
|
||||
|
||||
virtual void activateShapeTexture(int objectUniqueId, int jointIndex, int shapeIndex, int textureUniqueId);
|
||||
virtual void activateShapeTexture(int objectUniqueId, int jointIndex, int shapeIndex, int textureUniqueId);
|
||||
|
||||
virtual void syncTransform(int shapeUid, const class btTransform& worldTransform, const class btVector3& localScaling);
|
||||
|
||||
@@ -0,0 +1,57 @@
|
||||
|
||||
|
||||
project ("pybullet_tinyRendererPlugin")
|
||||
language "C++"
|
||||
kind "SharedLib"
|
||||
|
||||
includedirs {".","../../../../src", "../../../../examples",
|
||||
"../../../ThirdPartyLibs"}
|
||||
defines {"PHYSICS_IN_PROCESS_EXAMPLE_BROWSER"}
|
||||
hasCL = findOpenCL("clew")
|
||||
|
||||
links{"BulletCollision", "Bullet3Common", "LinearMath"}
|
||||
|
||||
if os.is("MacOSX") then
|
||||
-- targetextension {"so"}
|
||||
links{"Cocoa.framework","Python"}
|
||||
end
|
||||
|
||||
|
||||
files {
|
||||
"tinyRendererPlugin.cpp",
|
||||
"tinyRendererPlugin.h",
|
||||
"TinyRendererVisualShapeConverter.cpp",
|
||||
"TinyRendererVisualShapeConverter.h",
|
||||
"../../../Importers/ImportColladaDemo/LoadMeshFromCollada.cpp",
|
||||
"../../../Importers/ImportColladaDemo/LoadMeshFromCollada.h",
|
||||
"../../../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp",
|
||||
"../../../Importers/ImportMeshUtility/b3ImportMeshUtility.h",
|
||||
"../../../Importers/ImportObjDemo/LoadMeshFromObj.cpp",
|
||||
"../../../Importers/ImportObjDemo/LoadMeshFromObj.h",
|
||||
"../../../Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp",
|
||||
"../../../Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.h",
|
||||
"../../../TinyRenderer/geometry.cpp",
|
||||
"../../../TinyRenderer/model.cpp",
|
||||
"../../../TinyRenderer/our_gl.cpp",
|
||||
"../../../TinyRenderer/tgaimage.cpp",
|
||||
"../../../TinyRenderer/TinyRenderer.cpp",
|
||||
"../../../ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp",
|
||||
"../../../ThirdPartyLibs/Wavefront/tiny_obj_loader.h",
|
||||
"../../../ThirdPartyLibs/stb_image/stb_image.cpp",
|
||||
"../../../ThirdPartyLibs/stb_image/stb_image.h",
|
||||
"../../../ThirdPartyLibs/tinyxml/tinystr.cpp",
|
||||
"../../../ThirdPartyLibs/tinyxml/tinystr.h",
|
||||
"../../../ThirdPartyLibs/tinyxml/tinyxml.cpp",
|
||||
"../../../ThirdPartyLibs/tinyxml/tinyxml.h",
|
||||
"../../../ThirdPartyLibs/tinyxml/tinyxmlerror.cpp",
|
||||
"../../../ThirdPartyLibs/tinyxml/tinyxmlparser.cpp",
|
||||
"../../../OpenGLWindow/SimpleCamera.cpp",
|
||||
"../../../OpenGLWindow/SimpleCamera.h",
|
||||
"../../../Utils/b3Clock.cpp",
|
||||
"../../../Utils/b3Clock.h",
|
||||
"../../../Utils/b3ResourcePath.cpp",
|
||||
"../../../Utils/b3ResourcePath.h",
|
||||
}
|
||||
|
||||
|
||||
|
||||
@@ -0,0 +1,62 @@
|
||||
|
||||
//tinyRenderer plugin
|
||||
|
||||
/*
|
||||
import pybullet as p
|
||||
p.connect(p.GUI)
|
||||
pluginUid = p.loadPlugin("E:/develop/bullet3/bin/pybullet_testplugin_vs2010_x64_debug.dll")
|
||||
commandUid = 0
|
||||
argument = "plane.urdf"
|
||||
p.executePluginCommand(pluginUid,commandUid,argument)
|
||||
p.unloadPlugin(pluginUid)
|
||||
*/
|
||||
|
||||
#include "tinyRendererPlugin.h"
|
||||
#include "TinyRendererVisualShapeConverter.h"
|
||||
|
||||
#include "../../SharedMemoryPublic.h"
|
||||
#include "../b3PluginContext.h"
|
||||
#include <stdio.h>
|
||||
|
||||
|
||||
|
||||
struct MyRendererPluginClass
|
||||
{
|
||||
|
||||
TinyRendererVisualShapeConverter m_renderer;
|
||||
MyRendererPluginClass()
|
||||
{
|
||||
}
|
||||
virtual ~MyRendererPluginClass()
|
||||
{
|
||||
}
|
||||
};
|
||||
|
||||
B3_SHARED_API int initPlugin_tinyRendererPlugin(struct b3PluginContext* context)
|
||||
{
|
||||
MyRendererPluginClass* obj = new MyRendererPluginClass();
|
||||
context->m_userPointer = obj;
|
||||
return SHARED_MEMORY_MAGIC_NUMBER;
|
||||
}
|
||||
|
||||
|
||||
B3_SHARED_API int executePluginCommand_tinyRendererPlugin(struct b3PluginContext* context, const struct b3PluginArguments* arguments)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
|
||||
B3_SHARED_API void exitPlugin_tinyRendererPlugin(struct b3PluginContext* context)
|
||||
{
|
||||
MyRendererPluginClass* obj = (MyRendererPluginClass*) context->m_userPointer;
|
||||
delete obj;
|
||||
context->m_userPointer = 0;
|
||||
}
|
||||
|
||||
//all the APIs below are optional
|
||||
B3_SHARED_API struct UrdfRenderingInterface* getRenderInterface_tinyRendererPlugin(struct b3PluginContext* context)
|
||||
{
|
||||
MyRendererPluginClass* obj = (MyRendererPluginClass*) context->m_userPointer;
|
||||
return &obj->m_renderer;
|
||||
}
|
||||
|
||||
@@ -0,0 +1,25 @@
|
||||
#ifndef TINY_RENDERER_PLUGIN_H
|
||||
#define TINY_RENDERER_PLUGIN_H
|
||||
|
||||
#include "../b3PluginAPI.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
//initPlugin, exitPlugin and executePluginCommand are required, otherwise plugin won't load
|
||||
B3_SHARED_API int initPlugin_tinyRendererPlugin(struct b3PluginContext* context);
|
||||
B3_SHARED_API void exitPlugin_tinyRendererPlugin(struct b3PluginContext* context);
|
||||
B3_SHARED_API int executePluginCommand_tinyRendererPlugin(struct b3PluginContext* context, const struct b3PluginArguments* arguments);
|
||||
|
||||
//all the APIs below are optional
|
||||
B3_SHARED_API struct UrdfRenderingInterface* getRenderInterface_tinyRendererPlugin(struct b3PluginContext* context);
|
||||
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
};
|
||||
#endif
|
||||
|
||||
#endif//#define TEST_PLUGIN_H
|
||||
@@ -13,11 +13,10 @@ B3_SHARED_API int initPlugin_vrSyncPlugin(struct b3PluginContext* context);
|
||||
B3_SHARED_API void exitPlugin_vrSyncPlugin(struct b3PluginContext* context);
|
||||
B3_SHARED_API int executePluginCommand_vrSyncPlugin(struct b3PluginContext* context, const struct b3PluginArguments* arguments);
|
||||
|
||||
//preTickPluginCallback and postTickPluginCallback are optional.
|
||||
//optional APIs
|
||||
B3_SHARED_API int preTickPluginCallback_vrSyncPlugin(struct b3PluginContext* context);
|
||||
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
};
|
||||
#endif
|
||||
|
||||
@@ -55,13 +55,6 @@ myfiles =
|
||||
"PhysicsServerCommandProcessor.h",
|
||||
"b3PluginManager.cpp",
|
||||
"b3PluginManager.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",
|
||||
@@ -115,6 +108,20 @@ if (_OPTIONS["enable_static_vr_plugin"]) then
|
||||
files {"plugins/vrSyncPlugin/vrSyncPlugin.cpp"}
|
||||
end
|
||||
|
||||
if (not _OPTIONS["disable_static_tinyrenderer_plugin"]) then
|
||||
files
|
||||
{
|
||||
"plugins/tinyRendererPlugin/tinyRendererPlugin.cpp",
|
||||
"plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp",
|
||||
"../TinyRenderer/geometry.cpp",
|
||||
"../TinyRenderer/model.cpp",
|
||||
"../TinyRenderer/tgaimage.cpp",
|
||||
"../TinyRenderer/our_gl.cpp",
|
||||
"../TinyRenderer/TinyRenderer.cpp"
|
||||
}
|
||||
else
|
||||
defines("SKIP_STATIC_TINYRENDERER_PLUGIN")
|
||||
end
|
||||
|
||||
files {
|
||||
"../MultiThreading/b3ThreadSupportInterface.cpp",
|
||||
@@ -200,6 +207,21 @@ language "C++"
|
||||
|
||||
end
|
||||
|
||||
if (not _OPTIONS["disable_static_tinyrenderer_plugin"]) then
|
||||
files
|
||||
{
|
||||
"plugins/tinyRendererPlugin/tinyRendererPlugin.cpp",
|
||||
"plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp",
|
||||
"../TinyRenderer/geometry.cpp",
|
||||
"../TinyRenderer/model.cpp",
|
||||
"../TinyRenderer/tgaimage.cpp",
|
||||
"../TinyRenderer/our_gl.cpp",
|
||||
"../TinyRenderer/TinyRenderer.cpp"
|
||||
}
|
||||
else
|
||||
defines("SKIP_STATIC_TINYRENDERER_PLUGIN")
|
||||
end
|
||||
|
||||
|
||||
files {
|
||||
myfiles,
|
||||
@@ -344,7 +366,22 @@ if os.is("Windows") then
|
||||
initOpenGL()
|
||||
initGlew()
|
||||
|
||||
|
||||
if (not _OPTIONS["disable_static_tinyrenderer_plugin"]) then
|
||||
files
|
||||
{
|
||||
"plugins/tinyRendererPlugin/tinyRendererPlugin.cpp",
|
||||
"plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp",
|
||||
"../TinyRenderer/geometry.cpp",
|
||||
"../TinyRenderer/model.cpp",
|
||||
"../TinyRenderer/tgaimage.cpp",
|
||||
"../TinyRenderer/our_gl.cpp",
|
||||
"../TinyRenderer/TinyRenderer.cpp"
|
||||
}
|
||||
else
|
||||
defines("SKIP_STATIC_TINYRENDERER_PLUGIN")
|
||||
end
|
||||
|
||||
|
||||
files
|
||||
{
|
||||
myfiles,
|
||||
@@ -426,5 +463,6 @@ include "udp"
|
||||
include "tcp"
|
||||
include "plugins/testPlugin"
|
||||
include "plugins/vrSyncPlugin"
|
||||
include "plugins/tinyRendererPlugin"
|
||||
|
||||
|
||||
|
||||
@@ -90,9 +90,9 @@ myfiles =
|
||||
"../PhysicsServerCommandProcessor.h",
|
||||
"../b3PluginManager.cpp",
|
||||
"../PhysicsDirect.cpp",
|
||||
"../PhysicsClient.cpp",
|
||||
"../TinyRendererVisualShapeConverter.cpp",
|
||||
"../TinyRendererVisualShapeConverter.h",
|
||||
"../PhysicsClient.cpp",
|
||||
"../plugins/tinyRendererPlugin/tinyRendererPlugin.cpp",
|
||||
"../plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp",
|
||||
"../../TinyRenderer/geometry.cpp",
|
||||
"../../TinyRenderer/model.cpp",
|
||||
"../../TinyRenderer/tgaimage.cpp",
|
||||
|
||||
@@ -82,8 +82,8 @@ myfiles =
|
||||
"../b3PluginManager.cpp",
|
||||
"../PhysicsDirect.cpp",
|
||||
"../PhysicsClient.cpp",
|
||||
"../TinyRendererVisualShapeConverter.cpp",
|
||||
"../TinyRendererVisualShapeConverter.h",
|
||||
"../plugins/tinyRendererPlugin/tinyRendererPlugin.cpp",
|
||||
"../plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp",
|
||||
"../../TinyRenderer/geometry.cpp",
|
||||
"../../TinyRenderer/model.cpp",
|
||||
"../../TinyRenderer/tgaimage.cpp",
|
||||
|
||||
@@ -13,8 +13,8 @@ SET(RobotSimulator_SRCS
|
||||
../../examples/SharedMemory/IKTrajectoryHelper.cpp
|
||||
../../examples/SharedMemory/IKTrajectoryHelper.h
|
||||
../../examples/ExampleBrowser/InProcessExampleBrowser.cpp
|
||||
../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp
|
||||
../../examples/SharedMemory/TinyRendererVisualShapeConverter.h
|
||||
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp
|
||||
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp
|
||||
../../examples/OpenGLWindow/SimpleCamera.cpp
|
||||
../../examples/OpenGLWindow/SimpleCamera.h
|
||||
../../examples/TinyRenderer/geometry.cpp
|
||||
|
||||
@@ -18,8 +18,10 @@ SET(pybullet_SRCS
|
||||
../../examples/SharedMemory/IKTrajectoryHelper.cpp
|
||||
../../examples/SharedMemory/IKTrajectoryHelper.h
|
||||
../../examples/ExampleBrowser/InProcessExampleBrowser.cpp
|
||||
../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp
|
||||
../../examples/SharedMemory/TinyRendererVisualShapeConverter.h
|
||||
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp
|
||||
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.h
|
||||
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp
|
||||
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.h
|
||||
../../examples/OpenGLWindow/SimpleCamera.cpp
|
||||
../../examples/OpenGLWindow/SimpleCamera.h
|
||||
../../examples/TinyRenderer/geometry.cpp
|
||||
|
||||
9
examples/pybullet/examples/renderPlugin.py
Normal file
9
examples/pybullet/examples/renderPlugin.py
Normal file
@@ -0,0 +1,9 @@
|
||||
|
||||
import pybullet as p
|
||||
p.connect(p.GUI)
|
||||
plugin = p.loadPlugin("e:/develop/bullet3/bin/pybullet_tinyRendererPlugin_vs2010_x64_debug.dll","_tinyRendererPlugin")
|
||||
print("plugin=",plugin)
|
||||
p.loadURDF("r2d2.urdf")
|
||||
|
||||
while (1):
|
||||
p.getCameraImage(320,200)
|
||||
@@ -91,8 +91,10 @@ if not _OPTIONS["no-enet"] then
|
||||
"../../examples/SharedMemory/IKTrajectoryHelper.cpp",
|
||||
"../../examples/SharedMemory/IKTrajectoryHelper.h",
|
||||
"../../examples/ExampleBrowser/InProcessExampleBrowser.cpp",
|
||||
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp",
|
||||
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.h",
|
||||
"../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp",
|
||||
"../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.h",
|
||||
"../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp",
|
||||
"../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.h",
|
||||
"../../examples/OpenGLWindow/SimpleCamera.cpp",
|
||||
"../../examples/OpenGLWindow/SimpleCamera.h",
|
||||
"../../examples/TinyRenderer/geometry.cpp",
|
||||
|
||||
3
setup.py
3
setup.py
@@ -65,7 +65,8 @@ sources = ["examples/pybullet/pybullet.c"]\
|
||||
+["examples/SharedMemory/PhysicsClientC_API.cpp"]\
|
||||
+["examples/SharedMemory/Win32SharedMemory.cpp"]\
|
||||
+["examples/SharedMemory/PosixSharedMemory.cpp"]\
|
||||
+["examples/SharedMemory/TinyRendererVisualShapeConverter.cpp"]\
|
||||
+["examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp"]\
|
||||
+["examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp"]\
|
||||
+["examples/SharedMemory/PhysicsClientUDP.cpp"]\
|
||||
+["examples/SharedMemory/PhysicsClientUDP_C_API.cpp"]\
|
||||
+["examples/SharedMemory/PhysicsClientTCP.cpp"]\
|
||||
|
||||
@@ -66,8 +66,8 @@ ENDIF()
|
||||
../../examples/Utils/ChromeTraceUtil.h
|
||||
../../examples/Utils/RobotLoggingUtil.cpp
|
||||
../../examples/Utils/RobotLoggingUtil.h
|
||||
../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp
|
||||
../../examples/SharedMemory/TinyRendererVisualShapeConverter.h
|
||||
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp
|
||||
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp
|
||||
../../examples/OpenGLWindow/SimpleCamera.cpp
|
||||
../../examples/OpenGLWindow/SimpleCamera.h
|
||||
../../examples/TinyRenderer/geometry.cpp
|
||||
|
||||
@@ -191,8 +191,8 @@ project ("Test_PhysicsServerLoopBack")
|
||||
"../../examples/SharedMemory/Win32SharedMemory.h",
|
||||
"../../examples/SharedMemory/PosixSharedMemory.cpp",
|
||||
"../../examples/SharedMemory/PosixSharedMemory.h",
|
||||
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp",
|
||||
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.h",
|
||||
"../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp",
|
||||
"../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp",
|
||||
"../../examples/OpenGLWindow/SimpleCamera.cpp",
|
||||
"../../examples/OpenGLWindow/SimpleCamera.h",
|
||||
"../../examples/TinyRenderer/geometry.cpp",
|
||||
@@ -276,8 +276,8 @@ end
|
||||
"../../examples/SharedMemory/Win32SharedMemory.h",
|
||||
"../../examples/SharedMemory/PosixSharedMemory.cpp",
|
||||
"../../examples/SharedMemory/PosixSharedMemory.h",
|
||||
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp",
|
||||
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.h",
|
||||
"../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp",
|
||||
"../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp",
|
||||
"../../examples/TinyRenderer/geometry.cpp",
|
||||
"../../examples/TinyRenderer/model.cpp",
|
||||
"../../examples/TinyRenderer/tgaimage.cpp",
|
||||
@@ -388,8 +388,8 @@ project ("Test_PhysicsServerInProcessExampleBrowser")
|
||||
"../../examples/SharedMemory/Win32SharedMemory.h",
|
||||
"../../examples/SharedMemory/PosixSharedMemory.cpp",
|
||||
"../../examples/SharedMemory/PosixSharedMemory.h",
|
||||
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp",
|
||||
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.h",
|
||||
"../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp",
|
||||
"../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp",
|
||||
"../../examples/TinyRenderer/geometry.cpp",
|
||||
"../../examples/TinyRenderer/model.cpp",
|
||||
"../../examples/TinyRenderer/tgaimage.cpp",
|
||||
|
||||
Reference in New Issue
Block a user