First pass of load files through an interface (to allow loading from memory, zip file etc). So instead of posix fopen/fread, using CommonFileIOInterface.
A fileIO plugin can override custom file IO operations. As a small test, load files from a zipfile in memory. Default fileIO implementation is in examples/Utils/b3BulletDefaultFileIO.h Affects URDF, SDF, MJCF, Wavefront OBJ, STL, DAE, images.
This commit is contained in:
@@ -4,6 +4,8 @@
|
||||
#include "../Importers/ImportURDFDemo/BulletUrdfImporter.h"
|
||||
#include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h"
|
||||
#include "../Importers/ImportURDFDemo/URDF2Bullet.h"
|
||||
#include "../Importers/ImportURDFDemo/UrdfFindMeshFile.h"
|
||||
|
||||
#include "../Extras/InverseDynamics/btMultiBodyTreeCreator.hpp"
|
||||
|
||||
#include "BulletCollision/CollisionDispatch/btInternalEdgeUtility.h"
|
||||
@@ -54,6 +56,7 @@
|
||||
#include "plugins/collisionFilterPlugin/collisionFilterPlugin.h"
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef ENABLE_STATIC_GRPC_PLUGIN
|
||||
#include "plugins/grpcPlugin/grpcPlugin.h"
|
||||
#endif //ENABLE_STATIC_GRPC_PLUGIN
|
||||
@@ -74,6 +77,10 @@
|
||||
#include "plugins/tinyRendererPlugin/tinyRendererPlugin.h"
|
||||
#endif
|
||||
|
||||
#ifndef B3_ENABLE_FILEIO_PLUGIN
|
||||
#include "plugins/fileIOPlugin/fileIOPlugin.h"
|
||||
#endif//B3_DISABLE_FILEIO_PLUGIN
|
||||
|
||||
#ifdef B3_ENABLE_TINY_AUDIO
|
||||
#include "../TinyAudio/b3SoundEngine.h"
|
||||
#endif
|
||||
@@ -104,6 +111,11 @@ btQuaternion gVRTeleportOrn(0, 0, 0, 1);
|
||||
btScalar simTimeScalingFactor = 1;
|
||||
btScalar gRhsClamp = 1.f;
|
||||
|
||||
#include "../CommonInterfaces/CommonFileIOInterface.h"
|
||||
|
||||
|
||||
|
||||
|
||||
struct UrdfLinkNameMapUtil
|
||||
{
|
||||
btMultiBody* m_mb;
|
||||
@@ -1639,6 +1651,7 @@ struct PhysicsServerCommandProcessorInternalData
|
||||
std::string m_profileTimingFileName;
|
||||
|
||||
struct GUIHelperInterface* m_guiHelper;
|
||||
|
||||
int m_sharedMemoryKey;
|
||||
bool m_enableTinyRenderer;
|
||||
|
||||
@@ -1704,43 +1717,66 @@ struct PhysicsServerCommandProcessorInternalData
|
||||
{
|
||||
//register static plugins:
|
||||
#ifdef STATIC_LINK_VR_PLUGIN
|
||||
m_pluginManager.registerStaticLinkedPlugin("vrSyncPlugin", initPlugin_vrSyncPlugin, exitPlugin_vrSyncPlugin, executePluginCommand_vrSyncPlugin, preTickPluginCallback_vrSyncPlugin, 0, 0, 0, 0);
|
||||
b3PluginFunctions funcs(initPlugin_vrSyncPlugin,exitPlugin_vrSyncPlugin, executePluginCommand_vrSyncPlugin);
|
||||
funcs.m_preTickFunc = preTickPluginCallback_vrSyncPlugin;
|
||||
m_pluginManager.registerStaticLinkedPlugin("vrSyncPlugin", funcs);
|
||||
#endif //STATIC_LINK_VR_PLUGIN
|
||||
|
||||
}
|
||||
#ifndef SKIP_STATIC_PD_CONTROL_PLUGIN
|
||||
{
|
||||
m_pdControlPlugin = m_pluginManager.registerStaticLinkedPlugin("pdControlPlugin", initPlugin_pdControlPlugin, exitPlugin_pdControlPlugin, executePluginCommand_pdControlPlugin, preTickPluginCallback_pdControlPlugin, 0, 0, 0, 0);
|
||||
//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, PFN_TICK processClientCommandsFunc, PFN_GET_COLLISION_INTERFACE getCollisionFunc, bool initPlugin)
|
||||
b3PluginFunctions funcs(initPlugin_pdControlPlugin,exitPlugin_pdControlPlugin,executePluginCommand_pdControlPlugin);
|
||||
funcs.m_preTickFunc = preTickPluginCallback_pdControlPlugin;
|
||||
m_pdControlPlugin = m_pluginManager.registerStaticLinkedPlugin("pdControlPlugin", funcs);
|
||||
}
|
||||
#endif //SKIP_STATIC_PD_CONTROL_PLUGIN
|
||||
|
||||
#ifndef SKIP_COLLISION_FILTER_PLUGIN
|
||||
{
|
||||
m_collisionFilterPlugin = m_pluginManager.registerStaticLinkedPlugin("collisionFilterPlugin", initPlugin_collisionFilterPlugin, exitPlugin_collisionFilterPlugin, executePluginCommand_collisionFilterPlugin, 0, 0, 0, 0, getCollisionInterface_collisionFilterPlugin);
|
||||
b3PluginFunctions funcs(initPlugin_collisionFilterPlugin,exitPlugin_collisionFilterPlugin, executePluginCommand_collisionFilterPlugin);
|
||||
funcs.m_getCollisionFunc = getCollisionInterface_collisionFilterPlugin;
|
||||
m_collisionFilterPlugin = m_pluginManager.registerStaticLinkedPlugin("collisionFilterPlugin", funcs );
|
||||
m_pluginManager.selectCollisionPlugin(m_collisionFilterPlugin);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef ENABLE_STATIC_GRPC_PLUGIN
|
||||
{
|
||||
m_grpcPlugin = m_pluginManager.registerStaticLinkedPlugin("grpcPlugin", initPlugin_grpcPlugin, exitPlugin_grpcPlugin, executePluginCommand_grpcPlugin, 0, 0, 0, processClientCommands_grpcPlugin, 0);
|
||||
b3PluginFunctions funcs(initPlugin_grpcPlugin, exitPlugin_grpcPlugin, executePluginCommand_grpcPlugin);
|
||||
funcs.m_processClientCommandsFunc = processClientCommands_grpcPlugin;
|
||||
m_grpcPlugin = m_pluginManager.registerStaticLinkedPlugin("grpcPlugin", funcs);
|
||||
}
|
||||
#endif //ENABLE_STATIC_GRPC_PLUGIN
|
||||
|
||||
#ifdef STATIC_EGLRENDERER_PLUGIN
|
||||
{
|
||||
bool initPlugin = false;
|
||||
int renderPluginId = m_pluginManager.registerStaticLinkedPlugin("eglRendererPlugin", initPlugin_eglRendererPlugin, exitPlugin_eglRendererPlugin, executePluginCommand_eglRendererPlugin, 0, 0, getRenderInterface_eglRendererPlugin, 0, 0, initPlugin);
|
||||
b3PluginFunctions funcs(initPlugin_eglRendererPlugin, exitPlugin_eglRendererPlugin, executePluginCommand_eglRendererPlugin);
|
||||
funcs.m_getRendererFunc = getRenderInterface_eglRendererPlugin;
|
||||
int renderPluginId = m_pluginManager.registerStaticLinkedPlugin("eglRendererPlugin", funcs, initPlugin);
|
||||
m_pluginManager.selectPluginRenderer(renderPluginId);
|
||||
}
|
||||
#endif //STATIC_EGLRENDERER_PLUGIN
|
||||
|
||||
#ifndef SKIP_STATIC_TINYRENDERER_PLUGIN
|
||||
{
|
||||
int renderPluginId = m_pluginManager.registerStaticLinkedPlugin("tinyRendererPlugin", initPlugin_tinyRendererPlugin, exitPlugin_tinyRendererPlugin, executePluginCommand_tinyRendererPlugin, 0, 0, getRenderInterface_tinyRendererPlugin, 0, 0);
|
||||
b3PluginFunctions funcs(initPlugin_tinyRendererPlugin, exitPlugin_tinyRendererPlugin, executePluginCommand_tinyRendererPlugin);
|
||||
funcs.m_getRendererFunc=getRenderInterface_tinyRendererPlugin;
|
||||
int renderPluginId = m_pluginManager.registerStaticLinkedPlugin("tinyRendererPlugin", funcs);
|
||||
m_pluginManager.selectPluginRenderer(renderPluginId);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef B3_ENABLE_FILEIO_PLUGIN
|
||||
{
|
||||
b3PluginFunctions funcs(initPlugin_fileIOPlugin, exitPlugin_fileIOPlugin, executePluginCommand_fileIOPlugin);
|
||||
funcs.m_fileIoFunc = getFileIOFunc_fileIOPlugin;
|
||||
int renderPluginId = m_pluginManager.registerStaticLinkedPlugin("fileIOPlugin", funcs);
|
||||
m_pluginManager.selectFileIOPlugin(renderPluginId);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
m_vrControllerEvents.init();
|
||||
|
||||
@@ -2212,7 +2248,9 @@ struct ProgrammaticUrdfInterface : public URDFImporterInterface
|
||||
int graphicsIndex = -1;
|
||||
double globalScaling = 1.f; //todo!
|
||||
int flags = 0;
|
||||
BulletURDFImporter u2b(m_data->m_guiHelper, m_data->m_pluginManager.getRenderInterface(), globalScaling, flags);
|
||||
CommonFileIOInterface* fileIO = m_data->m_pluginManager.getFileIOInterface();
|
||||
|
||||
BulletURDFImporter u2b(m_data->m_guiHelper, m_data->m_pluginManager.getRenderInterface(),fileIO, globalScaling, flags);
|
||||
u2b.setEnableTinyRenderer(m_data->m_enableTinyRenderer);
|
||||
|
||||
btAlignedObjectArray<GLInstanceVertex> vertices;
|
||||
@@ -2300,7 +2338,8 @@ struct ProgrammaticUrdfInterface : public URDFImporterInterface
|
||||
//UrdfLink*const* linkPtr = model.m_links.getAtIndex(urdfIndex);
|
||||
if (m_data->m_pluginManager.getRenderInterface())
|
||||
{
|
||||
m_data->m_pluginManager.getRenderInterface()->convertVisualShapes(linkIndex, pathPrefix, localInertiaFrame, &link, &model, colObj->getBroadphaseHandle()->getUid(), bodyUniqueId);
|
||||
CommonFileIOInterface* fileIO = m_data->m_pluginManager.getFileIOInterface();
|
||||
m_data->m_pluginManager.getRenderInterface()->convertVisualShapes(linkIndex, pathPrefix, localInertiaFrame, &link, &model, colObj->getBroadphaseHandle()->getUid(), bodyUniqueId, fileIO);
|
||||
}
|
||||
}
|
||||
virtual void setBodyUniqueId(int bodyId)
|
||||
@@ -3015,7 +3054,8 @@ bool PhysicsServerCommandProcessor::loadMjcf(const char* fileName, char* bufferS
|
||||
|
||||
m_data->m_sdfRecentLoadedBodies.clear();
|
||||
|
||||
BulletMJCFImporter u2b(m_data->m_guiHelper, m_data->m_pluginManager.getRenderInterface(), flags);
|
||||
CommonFileIOInterface* fileIO = m_data->m_pluginManager.getFileIOInterface();
|
||||
BulletMJCFImporter u2b(m_data->m_guiHelper, m_data->m_pluginManager.getRenderInterface(), fileIO, flags);
|
||||
|
||||
bool useFixedBase = false;
|
||||
MyMJCFLogger2 logger;
|
||||
@@ -3037,8 +3077,8 @@ bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferSe
|
||||
}
|
||||
|
||||
m_data->m_sdfRecentLoadedBodies.clear();
|
||||
|
||||
BulletURDFImporter u2b(m_data->m_guiHelper, m_data->m_pluginManager.getRenderInterface(), globalScaling, flags);
|
||||
CommonFileIOInterface* fileIO = m_data->m_pluginManager.getFileIOInterface();
|
||||
BulletURDFImporter u2b(m_data->m_guiHelper, m_data->m_pluginManager.getRenderInterface(), fileIO, globalScaling, flags);
|
||||
u2b.setEnableTinyRenderer(m_data->m_enableTinyRenderer);
|
||||
|
||||
bool forceFixedBase = false;
|
||||
@@ -3067,7 +3107,8 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto
|
||||
return false;
|
||||
}
|
||||
|
||||
BulletURDFImporter u2b(m_data->m_guiHelper, m_data->m_pluginManager.getRenderInterface(), globalScaling, flags);
|
||||
CommonFileIOInterface* fileIO = m_data->m_pluginManager.getFileIOInterface();
|
||||
BulletURDFImporter u2b(m_data->m_guiHelper, m_data->m_pluginManager.getRenderInterface(), fileIO, globalScaling, flags);
|
||||
u2b.setEnableTinyRenderer(m_data->m_enableTinyRenderer);
|
||||
bool loadOk = u2b.loadURDF(fileName, useFixedBase);
|
||||
|
||||
@@ -4101,9 +4142,9 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str
|
||||
urdfColObj.m_geometry.m_meshFileName = fileName;
|
||||
|
||||
urdfColObj.m_geometry.m_meshScale = meshScale;
|
||||
|
||||
CommonFileIOInterface* fileIO = m_data->m_pluginManager.getFileIOInterface();
|
||||
pathPrefix[0] = 0;
|
||||
if (b3ResourcePath::findResourcePath(fileName.c_str(), relativeFileName, 1024))
|
||||
if (fileIO->findResourcePath(fileName.c_str(), relativeFileName, 1024))
|
||||
{
|
||||
b3FileUtils::extractPath(relativeFileName, pathPrefix, 1024);
|
||||
}
|
||||
@@ -4112,14 +4153,16 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str
|
||||
std::string out_found_filename;
|
||||
int out_type;
|
||||
|
||||
bool foundFile = findExistingMeshFile(pathPrefix, relativeFileName, error_message_prefix, &out_found_filename, &out_type);
|
||||
|
||||
bool foundFile = UrdfFindMeshFile(fileIO, pathPrefix, relativeFileName, error_message_prefix, &out_found_filename, &out_type);
|
||||
if (foundFile)
|
||||
{
|
||||
urdfColObj.m_geometry.m_meshFileType = out_type;
|
||||
|
||||
if (out_type == UrdfGeometry::FILE_STL)
|
||||
{
|
||||
glmesh = LoadMeshFromSTL(relativeFileName);
|
||||
CommonFileIOInterface* fileIO(m_data->m_pluginManager.getFileIOInterface());
|
||||
glmesh = LoadMeshFromSTL(relativeFileName,fileIO);
|
||||
}
|
||||
if (out_type == UrdfGeometry::FILE_OBJ)
|
||||
{
|
||||
@@ -4127,12 +4170,13 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str
|
||||
|
||||
if (clientCmd.m_createUserShapeArgs.m_shapes[i].m_collisionFlags & GEOM_FORCE_CONCAVE_TRIMESH)
|
||||
{
|
||||
glmesh = LoadMeshFromObj(relativeFileName, pathPrefix);
|
||||
CommonFileIOInterface* fileIO = m_data->m_pluginManager.getFileIOInterface();
|
||||
glmesh = LoadMeshFromObj(relativeFileName, pathPrefix,fileIO);
|
||||
}
|
||||
else
|
||||
{
|
||||
std::vector<tinyobj::shape_t> shapes;
|
||||
std::string err = tinyobj::LoadObj(shapes, out_found_filename.c_str());
|
||||
std::string err = tinyobj::LoadObj(shapes, out_found_filename.c_str(),"",fileIO);
|
||||
|
||||
//shape = createConvexHullFromShapes(shapes, collision->m_geometry.m_meshScale);
|
||||
//static btCollisionShape* createConvexHullFromShapes(std::vector<tinyobj::shape_t>& shapes, const btVector3& geomScale)
|
||||
@@ -4309,7 +4353,8 @@ 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_pluginManager.getRenderInterface(), globalScaling, flags);
|
||||
CommonFileIOInterface* fileIO = m_data->m_pluginManager.getFileIOInterface();
|
||||
BulletURDFImporter u2b(m_data->m_guiHelper, m_data->m_pluginManager.getRenderInterface(), fileIO, globalScaling, flags);
|
||||
u2b.setEnableTinyRenderer(m_data->m_enableTinyRenderer);
|
||||
btTransform localInertiaFrame;
|
||||
localInertiaFrame.setIdentity();
|
||||
@@ -4374,12 +4419,12 @@ bool PhysicsServerCommandProcessor::processCreateVisualShapeCommand(const struct
|
||||
const std::string& error_message_prefix = "";
|
||||
std::string out_found_filename;
|
||||
int out_type;
|
||||
if (b3ResourcePath::findResourcePath(fileName.c_str(), relativeFileName, 1024))
|
||||
if (fileIO->findResourcePath(fileName.c_str(), relativeFileName, 1024))
|
||||
{
|
||||
b3FileUtils::extractPath(relativeFileName, pathPrefix, 1024);
|
||||
}
|
||||
|
||||
bool foundFile = findExistingMeshFile(pathPrefix, relativeFileName, error_message_prefix, &out_found_filename, &out_type);
|
||||
bool foundFile = UrdfFindMeshFile(fileIO, pathPrefix, relativeFileName, error_message_prefix, &out_found_filename, &out_type);
|
||||
visualShape.m_geometry.m_meshFileType = out_type;
|
||||
visualShape.m_geometry.m_meshFileName = fileName;
|
||||
|
||||
@@ -6692,19 +6737,21 @@ bool PhysicsServerCommandProcessor::processLoadSoftBodyCommand(const struct Shar
|
||||
}
|
||||
|
||||
{
|
||||
CommonFileIOInterface* fileIO(m_data->m_pluginManager.getFileIOInterface());
|
||||
char relativeFileName[1024];
|
||||
char pathPrefix[1024];
|
||||
pathPrefix[0] = 0;
|
||||
if (b3ResourcePath::findResourcePath(loadSoftBodyArgs.m_fileName, relativeFileName, 1024))
|
||||
if (fileIO->findResourcePath(loadSoftBodyArgs.m_fileName, relativeFileName, 1024))
|
||||
{
|
||||
b3FileUtils::extractPath(relativeFileName, pathPrefix, 1024);
|
||||
}
|
||||
const std::string& error_message_prefix = "";
|
||||
std::string out_found_filename;
|
||||
int out_type;
|
||||
bool foundFile = findExistingMeshFile(pathPrefix, relativeFileName, error_message_prefix, &out_found_filename, &out_type);
|
||||
|
||||
bool foundFile = UrdfFindMeshFile(fileIO,pathPrefix, relativeFileName, error_message_prefix, &out_found_filename, &out_type);
|
||||
std::vector<tinyobj::shape_t> shapes;
|
||||
std::string err = tinyobj::LoadObj(shapes, out_found_filename.c_str());
|
||||
std::string err = tinyobj::LoadObj(shapes, out_found_filename.c_str(),"",fileIO);
|
||||
if (shapes.size() > 0)
|
||||
{
|
||||
const tinyobj::shape_t& shape = shapes[0];
|
||||
@@ -9802,7 +9849,8 @@ bool PhysicsServerCommandProcessor::processLoadTextureCommand(const struct Share
|
||||
char relativeFileName[1024];
|
||||
char pathPrefix[1024];
|
||||
|
||||
if (b3ResourcePath::findResourcePath(clientCmd.m_loadTextureArguments.m_textureFileName, relativeFileName, 1024))
|
||||
CommonFileIOInterface* fileIO(m_data->m_pluginManager.getFileIOInterface());
|
||||
if (fileIO->findResourcePath(clientCmd.m_loadTextureArguments.m_textureFileName, relativeFileName, 1024))
|
||||
{
|
||||
b3FileUtils::extractPath(relativeFileName, pathPrefix, 1024);
|
||||
|
||||
|
||||
@@ -1520,48 +1520,51 @@ public:
|
||||
|
||||
if (gEnableDefaultKeyboardShortcuts)
|
||||
{
|
||||
if (key == 'w' && state)
|
||||
if (m_guiHelper->getAppInterface()->m_renderer->getActiveCamera()->isVRCamera())
|
||||
{
|
||||
VRTeleportPos[0] += shift;
|
||||
m_physicsServer.setVRTeleportPosition(VRTeleportPos);
|
||||
saveCurrentSettingsVR(VRTeleportPos);
|
||||
}
|
||||
if (key == 's' && state)
|
||||
{
|
||||
VRTeleportPos[0] -= shift;
|
||||
m_physicsServer.setVRTeleportPosition(VRTeleportPos);
|
||||
saveCurrentSettingsVR(VRTeleportPos);
|
||||
}
|
||||
if (key == 'a' && state)
|
||||
{
|
||||
VRTeleportPos[1] -= shift;
|
||||
m_physicsServer.setVRTeleportPosition(VRTeleportPos);
|
||||
saveCurrentSettingsVR(VRTeleportPos);
|
||||
}
|
||||
if (key == 'd' && state)
|
||||
{
|
||||
VRTeleportPos[1] += shift;
|
||||
m_physicsServer.setVRTeleportPosition(VRTeleportPos);
|
||||
saveCurrentSettingsVR(VRTeleportPos);
|
||||
}
|
||||
if (key == 'q' && state)
|
||||
{
|
||||
VRTeleportPos[2] += shift;
|
||||
m_physicsServer.setVRTeleportPosition(VRTeleportPos);
|
||||
saveCurrentSettingsVR(VRTeleportPos);
|
||||
}
|
||||
if (key == 'e' && state)
|
||||
{
|
||||
VRTeleportPos[2] -= shift;
|
||||
m_physicsServer.setVRTeleportPosition(VRTeleportPos);
|
||||
saveCurrentSettingsVR(VRTeleportPos);
|
||||
}
|
||||
if (key == 'z' && state)
|
||||
{
|
||||
gVRTeleportRotZ += shift;
|
||||
btQuaternion VRTeleportOrn = btQuaternion(btVector3(0, 0, 1), gVRTeleportRotZ);
|
||||
m_physicsServer.setVRTeleportOrientation(VRTeleportOrn);
|
||||
saveCurrentSettingsVR(VRTeleportPos);
|
||||
if (key == 'w' && state)
|
||||
{
|
||||
VRTeleportPos[0] += shift;
|
||||
m_physicsServer.setVRTeleportPosition(VRTeleportPos);
|
||||
saveCurrentSettingsVR(VRTeleportPos);
|
||||
}
|
||||
if (key == 's' && state)
|
||||
{
|
||||
VRTeleportPos[0] -= shift;
|
||||
m_physicsServer.setVRTeleportPosition(VRTeleportPos);
|
||||
saveCurrentSettingsVR(VRTeleportPos);
|
||||
}
|
||||
if (key == 'a' && state)
|
||||
{
|
||||
VRTeleportPos[1] -= shift;
|
||||
m_physicsServer.setVRTeleportPosition(VRTeleportPos);
|
||||
saveCurrentSettingsVR(VRTeleportPos);
|
||||
}
|
||||
if (key == 'd' && state)
|
||||
{
|
||||
VRTeleportPos[1] += shift;
|
||||
m_physicsServer.setVRTeleportPosition(VRTeleportPos);
|
||||
saveCurrentSettingsVR(VRTeleportPos);
|
||||
}
|
||||
if (key == 'q' && state)
|
||||
{
|
||||
VRTeleportPos[2] += shift;
|
||||
m_physicsServer.setVRTeleportPosition(VRTeleportPos);
|
||||
saveCurrentSettingsVR(VRTeleportPos);
|
||||
}
|
||||
if (key == 'e' && state)
|
||||
{
|
||||
VRTeleportPos[2] -= shift;
|
||||
m_physicsServer.setVRTeleportPosition(VRTeleportPos);
|
||||
saveCurrentSettingsVR(VRTeleportPos);
|
||||
}
|
||||
if (key == 'z' && state)
|
||||
{
|
||||
gVRTeleportRotZ += shift;
|
||||
btQuaternion VRTeleportOrn = btQuaternion(btVector3(0, 0, 1), gVRTeleportRotZ);
|
||||
m_physicsServer.setVRTeleportOrientation(VRTeleportOrn);
|
||||
saveCurrentSettingsVR(VRTeleportPos);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
#include "PhysicsClientC_API.h"
|
||||
#include "PhysicsDirect.h"
|
||||
#include "plugins/b3PluginContext.h"
|
||||
|
||||
#include "../Utils/b3BulletDefaultFileIO.h"
|
||||
#ifdef _WIN32
|
||||
#define WIN32_LEAN_AND_MEAN
|
||||
#define VC_EXTRALEAN
|
||||
@@ -48,6 +48,7 @@ struct b3Plugin
|
||||
|
||||
PFN_GET_RENDER_INTERFACE m_getRendererFunc;
|
||||
PFN_GET_COLLISION_INTERFACE m_getCollisionFunc;
|
||||
PFN_GET_FILEIO_INTERFACE m_getFileIOFunc;
|
||||
|
||||
void* m_userPointer;
|
||||
|
||||
@@ -65,6 +66,7 @@ struct b3Plugin
|
||||
m_processClientCommandsFunc(0),
|
||||
m_getRendererFunc(0),
|
||||
m_getCollisionFunc(0),
|
||||
m_getFileIOFunc(0),
|
||||
m_userPointer(0)
|
||||
{
|
||||
}
|
||||
@@ -84,6 +86,7 @@ struct b3Plugin
|
||||
m_processClientCommandsFunc = 0;
|
||||
m_getRendererFunc = 0;
|
||||
m_getCollisionFunc = 0;
|
||||
m_getFileIOFunc = 0;
|
||||
m_userPointer = 0;
|
||||
m_isInitialized = false;
|
||||
}
|
||||
@@ -105,9 +108,11 @@ struct b3PluginManagerInternalData
|
||||
int m_activeRendererPluginUid;
|
||||
int m_activeCollisionPluginUid;
|
||||
int m_numNotificationPlugins;
|
||||
|
||||
int m_activeFileIOPluginUid;
|
||||
b3BulletDefaultFileIO m_defaultFileIO;
|
||||
|
||||
b3PluginManagerInternalData()
|
||||
: m_rpcCommandProcessorInterface(0), m_activeNotificationsBufferIndex(0), m_activeRendererPluginUid(-1), m_activeCollisionPluginUid(-1), m_numNotificationPlugins(0)
|
||||
: m_rpcCommandProcessorInterface(0), m_activeNotificationsBufferIndex(0), m_activeRendererPluginUid(-1), m_activeCollisionPluginUid(-1), m_numNotificationPlugins(0), m_activeFileIOPluginUid(-1)
|
||||
{
|
||||
}
|
||||
};
|
||||
@@ -208,7 +213,8 @@ int b3PluginManager::loadPlugin(const char* pluginPath, const char* postFixStr)
|
||||
std::string processClientCommandsStr = std::string("processClientCommands") + postFix;
|
||||
std::string getRendererStr = std::string("getRenderInterface") + postFix;
|
||||
std::string getCollisionStr = std::string("getCollisionInterface") + postFix;
|
||||
|
||||
std::string getFileIOStr = std::string("getFileIOInterface") + 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());
|
||||
@@ -224,6 +230,8 @@ int b3PluginManager::loadPlugin(const char* pluginPath, const char* postFixStr)
|
||||
|
||||
plugin->m_getRendererFunc = (PFN_GET_RENDER_INTERFACE)B3_DYNLIB_IMPORT(pluginHandle, getRendererStr.c_str());
|
||||
plugin->m_getCollisionFunc = (PFN_GET_COLLISION_INTERFACE)B3_DYNLIB_IMPORT(pluginHandle, getCollisionStr.c_str());
|
||||
plugin->m_getFileIOFunc = (PFN_GET_FILEIO_INTERFACE)B3_DYNLIB_IMPORT(pluginHandle, getFileIOStr.c_str());
|
||||
|
||||
|
||||
if (plugin->m_initFunc && plugin->m_exitFunc && plugin->m_executeCommandFunc)
|
||||
{
|
||||
@@ -293,6 +301,15 @@ int b3PluginManager::loadPlugin(const char* pluginPath, const char* postFixStr)
|
||||
selectCollisionPlugin(pluginUniqueId);
|
||||
}
|
||||
}
|
||||
//for now, automatically select the loaded plugin as active fileIO plugin.
|
||||
if (pluginUniqueId >= 0)
|
||||
{
|
||||
b3PluginHandle* plugin = m_data->m_plugins.getHandle(pluginUniqueId);
|
||||
if (plugin && plugin->m_getFileIOFunc)
|
||||
{
|
||||
selectFileIOPlugin(pluginUniqueId);
|
||||
}
|
||||
}
|
||||
|
||||
return pluginUniqueId;
|
||||
}
|
||||
@@ -438,7 +455,9 @@ int b3PluginManager::executePluginCommand(int pluginUniqueId, const b3PluginArgu
|
||||
return result;
|
||||
}
|
||||
|
||||
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, PFN_TICK processClientCommandsFunc, PFN_GET_COLLISION_INTERFACE getCollisionFunc, bool initPlugin)
|
||||
|
||||
|
||||
int b3PluginManager::registerStaticLinkedPlugin(const char* pluginPath, b3PluginFunctions& functions, bool initPlugin)
|
||||
{
|
||||
b3Plugin orgPlugin;
|
||||
|
||||
@@ -447,14 +466,15 @@ int b3PluginManager::registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT
|
||||
pluginHandle->m_pluginHandle = 0;
|
||||
pluginHandle->m_ownsPluginHandle = false;
|
||||
pluginHandle->m_pluginUniqueId = pluginUniqueId;
|
||||
pluginHandle->m_executeCommandFunc = executeCommandFunc;
|
||||
pluginHandle->m_exitFunc = exitFunc;
|
||||
pluginHandle->m_initFunc = initFunc;
|
||||
pluginHandle->m_preTickFunc = preTickFunc;
|
||||
pluginHandle->m_postTickFunc = postTickFunc;
|
||||
pluginHandle->m_getRendererFunc = getRendererFunc;
|
||||
pluginHandle->m_getCollisionFunc = getCollisionFunc;
|
||||
pluginHandle->m_processClientCommandsFunc = processClientCommandsFunc;
|
||||
pluginHandle->m_executeCommandFunc = functions.m_executeCommandFunc;
|
||||
pluginHandle->m_exitFunc = functions.m_exitFunc;
|
||||
pluginHandle->m_initFunc = functions.m_initFunc;
|
||||
pluginHandle->m_preTickFunc = functions.m_preTickFunc;
|
||||
pluginHandle->m_postTickFunc = functions.m_postTickFunc;
|
||||
pluginHandle->m_getRendererFunc = functions.m_getRendererFunc;
|
||||
pluginHandle->m_getCollisionFunc = functions.m_getCollisionFunc;
|
||||
pluginHandle->m_processClientCommandsFunc = functions.m_processClientCommandsFunc;
|
||||
pluginHandle->m_getFileIOFunc = functions.m_fileIoFunc;
|
||||
pluginHandle->m_pluginHandle = 0;
|
||||
pluginHandle->m_pluginPath = pluginPath;
|
||||
pluginHandle->m_userPointer = 0;
|
||||
@@ -502,6 +522,32 @@ UrdfRenderingInterface* b3PluginManager::getRenderInterface()
|
||||
return renderer;
|
||||
}
|
||||
|
||||
void b3PluginManager::selectFileIOPlugin(int pluginUniqueId)
|
||||
{
|
||||
m_data->m_activeFileIOPluginUid = pluginUniqueId;
|
||||
}
|
||||
|
||||
struct CommonFileIOInterface* b3PluginManager::getFileIOInterface()
|
||||
{
|
||||
CommonFileIOInterface* fileIOInterface = 0;
|
||||
if (m_data->m_activeFileIOPluginUid >= 0)
|
||||
{
|
||||
b3PluginHandle* plugin = m_data->m_plugins.getHandle(m_data->m_activeFileIOPluginUid);
|
||||
if (plugin && plugin->m_getFileIOFunc)
|
||||
{
|
||||
b3PluginContext context = {0};
|
||||
context.m_userPointer = plugin->m_userPointer;
|
||||
context.m_physClient = (b3PhysicsClientHandle)m_data->m_physicsDirect;
|
||||
fileIOInterface = plugin->m_getFileIOFunc(&context);
|
||||
}
|
||||
}
|
||||
if (fileIOInterface==0)
|
||||
{
|
||||
return &m_data->m_defaultFileIO;
|
||||
}
|
||||
return fileIOInterface;
|
||||
}
|
||||
|
||||
void b3PluginManager::selectCollisionPlugin(int pluginUniqueId)
|
||||
{
|
||||
m_data->m_activeCollisionPluginUid = pluginUniqueId;
|
||||
|
||||
@@ -10,6 +10,37 @@ enum b3PluginManagerTickMode
|
||||
B3_PROCESS_CLIENT_COMMANDS_TICK,
|
||||
};
|
||||
|
||||
struct b3PluginFunctions
|
||||
{
|
||||
//required
|
||||
PFN_INIT m_initFunc;
|
||||
PFN_EXIT m_exitFunc;
|
||||
PFN_EXECUTE m_executeCommandFunc;
|
||||
|
||||
//optional
|
||||
PFN_TICK m_preTickFunc;
|
||||
PFN_TICK m_postTickFunc;
|
||||
PFN_GET_RENDER_INTERFACE m_getRendererFunc;
|
||||
PFN_TICK m_processClientCommandsFunc;
|
||||
PFN_TICK m_processNotificationsFunc;
|
||||
PFN_GET_COLLISION_INTERFACE m_getCollisionFunc;
|
||||
PFN_GET_FILEIO_INTERFACE m_fileIoFunc;
|
||||
|
||||
b3PluginFunctions(PFN_INIT initFunc, PFN_EXIT exitFunc, PFN_EXECUTE executeCommandFunc)
|
||||
:m_initFunc(initFunc),
|
||||
m_exitFunc(exitFunc),
|
||||
m_executeCommandFunc(executeCommandFunc),
|
||||
m_preTickFunc(0),
|
||||
m_postTickFunc(0),
|
||||
m_getRendererFunc(0),
|
||||
m_processClientCommandsFunc(0),
|
||||
m_processNotificationsFunc(0),
|
||||
m_getCollisionFunc(0),
|
||||
m_fileIoFunc(0)
|
||||
{
|
||||
}
|
||||
};
|
||||
|
||||
class b3PluginManager
|
||||
{
|
||||
struct b3PluginManagerInternalData* m_data;
|
||||
@@ -29,11 +60,14 @@ public:
|
||||
|
||||
void tickPlugins(double timeStep, b3PluginManagerTickMode tickMode);
|
||||
|
||||
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, PFN_TICK processClientCommandsFunc, PFN_GET_COLLISION_INTERFACE getCollisionFunc, bool initPlugin = true);
|
||||
int registerStaticLinkedPlugin(const char* pluginPath, b3PluginFunctions& functions, bool initPlugin = true);
|
||||
|
||||
void selectPluginRenderer(int pluginUniqueId);
|
||||
struct UrdfRenderingInterface* getRenderInterface();
|
||||
|
||||
void selectFileIOPlugin(int pluginUniqueId);
|
||||
struct CommonFileIOInterface* getFileIOInterface();
|
||||
|
||||
void selectCollisionPlugin(int pluginUniqueId);
|
||||
struct b3PluginCollisionInterface* getCollisionInterface();
|
||||
};
|
||||
|
||||
@@ -31,7 +31,7 @@ extern "C"
|
||||
|
||||
typedef B3_API_ENTRY struct UrdfRenderingInterface*(B3_API_CALL* PFN_GET_RENDER_INTERFACE)(struct b3PluginContext* context);
|
||||
typedef B3_API_ENTRY struct b3PluginCollisionInterface*(B3_API_CALL* PFN_GET_COLLISION_INTERFACE)(struct b3PluginContext* context);
|
||||
|
||||
typedef B3_API_ENTRY struct CommonFileIOInterface*(B3_API_CALL* PFN_GET_FILEIO_INTERFACE)(struct b3PluginContext* context);
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
1
examples/SharedMemory/plugins/b3PluginFileIOInterface.h
Normal file
1
examples/SharedMemory/plugins/b3PluginFileIOInterface.h
Normal file
@@ -0,0 +1 @@
|
||||
#error
|
||||
333
examples/SharedMemory/plugins/fileIOPlugin/fileIOPlugin.cpp
Normal file
333
examples/SharedMemory/plugins/fileIOPlugin/fileIOPlugin.cpp
Normal file
@@ -0,0 +1,333 @@
|
||||
|
||||
|
||||
#include "fileIOPlugin.h"
|
||||
#include "../../SharedMemoryPublic.h"
|
||||
#include "../b3PluginContext.h"
|
||||
#include <stdio.h>
|
||||
#include "../../../CommonInterfaces/CommonFileIOInterface.h"
|
||||
#include "../../../Utils/b3ResourcePath.h"
|
||||
#include "../../../Utils/b3BulletDefaultFileIO.h"
|
||||
|
||||
|
||||
//#define B3_USE_ZLIB
|
||||
#ifdef B3_USE_ZLIB
|
||||
|
||||
#include "minizip/unzip.h"
|
||||
|
||||
struct MyFileIO : public CommonFileIOInterface
|
||||
{
|
||||
std::string m_zipfileName;
|
||||
|
||||
unzFile m_fileHandles[FILEIO_MAX_FILES];
|
||||
int m_numFileHandles;
|
||||
|
||||
MyFileIO(const char* zipfileName)
|
||||
:m_zipfileName(zipfileName),
|
||||
m_numFileHandles(0)
|
||||
{
|
||||
for (int i=0;i<FILEIO_MAX_FILES;i++)
|
||||
{
|
||||
m_fileHandles[i]=0;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
static bool FileIOPluginFindFile(void* userPtr, const char* orgFileName, char* relativeFileName, int maxRelativeFileNameMaxLen)
|
||||
{
|
||||
MyFileIO* fileIo = (MyFileIO*) userPtr;
|
||||
return fileIo->findFile(orgFileName, relativeFileName, maxRelativeFileNameMaxLen);
|
||||
}
|
||||
|
||||
virtual ~MyFileIO()
|
||||
{
|
||||
}
|
||||
virtual int fileOpen(const char* fileName, const char* mode)
|
||||
{
|
||||
//search a free slot
|
||||
int slot = -1;
|
||||
for (int i=0;i<FILEIO_MAX_FILES;i++)
|
||||
{
|
||||
if (m_fileHandles[i]==0)
|
||||
{
|
||||
slot=i;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (slot>=0)
|
||||
{
|
||||
unzFile zipfile;
|
||||
unz_global_info m_global_info;
|
||||
zipfile = unzOpen(m_zipfileName.c_str());
|
||||
if (zipfile == NULL)
|
||||
{
|
||||
printf("%s: not found\n", m_zipfileName.c_str());
|
||||
slot = -1;
|
||||
} else
|
||||
{
|
||||
int result = 0;
|
||||
result = unzGetGlobalInfo(zipfile, &m_global_info );
|
||||
if (result != UNZ_OK)
|
||||
{
|
||||
printf("could not read file global info from %s\n", m_zipfileName.c_str());
|
||||
unzClose(zipfile);
|
||||
zipfile = 0;
|
||||
slot = -1;
|
||||
} else
|
||||
{
|
||||
m_fileHandles[slot] = zipfile;
|
||||
}
|
||||
}
|
||||
if (slot >=0)
|
||||
{
|
||||
int result = unzLocateFile(zipfile, fileName, 0);
|
||||
if (result == UNZ_OK)
|
||||
{
|
||||
unz_file_info info;
|
||||
result = unzGetCurrentFileInfo(zipfile, &info, NULL, 0, NULL, 0, NULL, 0);
|
||||
if (result != UNZ_OK)
|
||||
{
|
||||
printf("unzGetCurrentFileInfo() != UNZ_OK (%d)\n", result);
|
||||
slot=-1;
|
||||
}
|
||||
else
|
||||
{
|
||||
result = unzOpenCurrentFile(zipfile);
|
||||
if (result == UNZ_OK)
|
||||
{
|
||||
} else
|
||||
{
|
||||
slot=-1;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
return slot;
|
||||
}
|
||||
virtual int fileRead(int fileHandle, char* destBuffer, int numBytes)
|
||||
{
|
||||
int result = -1;
|
||||
if (fileHandle>=0 && fileHandle < FILEIO_MAX_FILES)
|
||||
{
|
||||
unzFile f = m_fileHandles[fileHandle];
|
||||
if (f)
|
||||
{
|
||||
result = unzReadCurrentFile(f, destBuffer,numBytes);
|
||||
//::fread(destBuffer, 1, numBytes, f);
|
||||
}
|
||||
}
|
||||
return result;
|
||||
|
||||
}
|
||||
virtual int fileWrite(int fileHandle,const char* sourceBuffer, int numBytes)
|
||||
{
|
||||
#if 0
|
||||
if (fileHandle>=0 && fileHandle < FILEIO_MAX_FILES)
|
||||
{
|
||||
FILE* f = m_fileHandles[fileHandle];
|
||||
if (f)
|
||||
{
|
||||
return ::fwrite(sourceBuffer, 1, numBytes,m_fileHandles[fileHandle]);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
return -1;
|
||||
}
|
||||
virtual void fileClose(int fileHandle)
|
||||
{
|
||||
if (fileHandle>=0 && fileHandle < FILEIO_MAX_FILES)
|
||||
{
|
||||
unzFile f = m_fileHandles[fileHandle];
|
||||
if (f)
|
||||
{
|
||||
unzClose(f);
|
||||
m_fileHandles[fileHandle]=0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
virtual bool findResourcePath(const char* fileName, char* relativeFileName, int relativeFileNameSizeInBytes)
|
||||
{
|
||||
return b3ResourcePath::findResourcePath(fileName, relativeFileName, relativeFileNameSizeInBytes, MyFileIO::FileIOPluginFindFile, this);
|
||||
}
|
||||
|
||||
|
||||
virtual bool findFile(const char* orgFileName, char* relativeFileName, int maxRelativeFileNameMaxLen)
|
||||
{
|
||||
int fileHandle = -1;
|
||||
fileHandle = fileOpen(orgFileName, "rb");
|
||||
if (fileHandle>=0)
|
||||
{
|
||||
//printf("original file found: [%s]\n", orgFileName);
|
||||
sprintf(relativeFileName, "%s", orgFileName);
|
||||
fileClose(fileHandle);
|
||||
return true;
|
||||
}
|
||||
|
||||
//printf("Trying various directories, relative to current working directory\n");
|
||||
const char* prefix[] = {"./", "./data/", "../data/", "../../data/", "../../../data/", "../../../../data/"};
|
||||
int numPrefixes = sizeof(prefix) / sizeof(const char*);
|
||||
|
||||
int f = 0;
|
||||
bool fileFound = false;
|
||||
|
||||
for (int i = 0; !f && i < numPrefixes; i++)
|
||||
{
|
||||
#ifdef _MSC_VER
|
||||
sprintf_s(relativeFileName, maxRelativeFileNameMaxLen, "%s%s", prefix[i], orgFileName);
|
||||
#else
|
||||
sprintf(relativeFileName, "%s%s", prefix[i], orgFileName);
|
||||
#endif
|
||||
f = fileOpen(relativeFileName, "rb");
|
||||
if (f>=0)
|
||||
{
|
||||
fileFound = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (f>=0)
|
||||
{
|
||||
fileClose(f);
|
||||
}
|
||||
|
||||
return fileFound;
|
||||
}
|
||||
virtual char* readLine(int fileHandle, char* destBuffer, int numBytes)
|
||||
{
|
||||
int numRead = 0;
|
||||
|
||||
if (fileHandle>=0 && fileHandle < FILEIO_MAX_FILES)
|
||||
{
|
||||
unzFile f = m_fileHandles[fileHandle];
|
||||
if (f)
|
||||
{
|
||||
//return ::fgets(destBuffer, numBytes, m_fileHandles[fileHandle]);
|
||||
char c = 0;
|
||||
do
|
||||
{
|
||||
fileRead(fileHandle,&c,1);
|
||||
if (c && c!='\n')
|
||||
{
|
||||
if (c!=13)
|
||||
{
|
||||
destBuffer[numRead++]=c;
|
||||
} else
|
||||
{
|
||||
destBuffer[numRead++]=0;
|
||||
}
|
||||
}
|
||||
} while (c != 0 && c != '\n' && numRead<(numBytes-1));
|
||||
}
|
||||
}
|
||||
if (numRead<numBytes && numRead>0)
|
||||
{
|
||||
destBuffer[numRead]=0;
|
||||
return &destBuffer[0];
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
virtual int getFileSize(int fileHandle)
|
||||
{
|
||||
int size=0;
|
||||
|
||||
if (fileHandle>=0 && fileHandle < FILEIO_MAX_FILES)
|
||||
{
|
||||
unzFile f = m_fileHandles[fileHandle];
|
||||
if (f)
|
||||
{
|
||||
unz_file_info info;
|
||||
int result = unzGetCurrentFileInfo(f, &info, NULL, 0, NULL, 0, NULL, 0);
|
||||
if (result == UNZ_OK)
|
||||
{
|
||||
size = info.uncompressed_size;
|
||||
}
|
||||
}
|
||||
}
|
||||
return size;
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
|
||||
|
||||
#else
|
||||
typedef b3BulletDefaultFileIO MyFileIO;
|
||||
#endif
|
||||
|
||||
struct FileIOClass
|
||||
{
|
||||
int m_testData;
|
||||
|
||||
MyFileIO m_fileIO;
|
||||
|
||||
FileIOClass()
|
||||
: m_testData(42),
|
||||
m_fileIO()//"e:/develop/bullet3/data/plane.zip")
|
||||
{
|
||||
}
|
||||
virtual ~FileIOClass()
|
||||
{
|
||||
}
|
||||
};
|
||||
|
||||
B3_SHARED_API int initPlugin_fileIOPlugin(struct b3PluginContext* context)
|
||||
{
|
||||
FileIOClass* obj = new FileIOClass();
|
||||
context->m_userPointer = obj;
|
||||
return SHARED_MEMORY_MAGIC_NUMBER;
|
||||
}
|
||||
|
||||
|
||||
B3_SHARED_API int executePluginCommand_fileIOPlugin(struct b3PluginContext* context, const struct b3PluginArguments* arguments)
|
||||
{
|
||||
printf("text argument:%s\n", arguments->m_text);
|
||||
printf("int args: [");
|
||||
for (int i = 0; i < arguments->m_numInts; i++)
|
||||
{
|
||||
printf("%d", arguments->m_ints[i]);
|
||||
if ((i + 1) < arguments->m_numInts)
|
||||
{
|
||||
printf(",");
|
||||
}
|
||||
}
|
||||
printf("]\nfloat args: [");
|
||||
for (int i = 0; i < arguments->m_numFloats; i++)
|
||||
{
|
||||
printf("%f", arguments->m_floats[i]);
|
||||
if ((i + 1) < arguments->m_numFloats)
|
||||
{
|
||||
printf(",");
|
||||
}
|
||||
}
|
||||
printf("]\n");
|
||||
|
||||
FileIOClass* obj = (FileIOClass*)context->m_userPointer;
|
||||
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int statusType = -1;
|
||||
int bodyUniqueId = -1;
|
||||
|
||||
b3SharedMemoryCommandHandle command =
|
||||
b3LoadUrdfCommandInit(context->m_physClient, arguments->m_text);
|
||||
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(context->m_physClient, command);
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
if (statusType == CMD_URDF_LOADING_COMPLETED)
|
||||
{
|
||||
bodyUniqueId = b3GetStatusBodyIndex(statusHandle);
|
||||
}
|
||||
return bodyUniqueId;
|
||||
}
|
||||
|
||||
B3_SHARED_API struct CommonFileIOInterface* getFileIOFunc_fileIOPlugin(struct b3PluginContext* context)
|
||||
{
|
||||
FileIOClass* obj = (FileIOClass*)context->m_userPointer;
|
||||
return &obj->m_fileIO;
|
||||
}
|
||||
|
||||
B3_SHARED_API void exitPlugin_fileIOPlugin(struct b3PluginContext* context)
|
||||
{
|
||||
FileIOClass* obj = (FileIOClass*)context->m_userPointer;
|
||||
delete obj;
|
||||
context->m_userPointer = 0;
|
||||
}
|
||||
24
examples/SharedMemory/plugins/fileIOPlugin/fileIOPlugin.h
Normal file
24
examples/SharedMemory/plugins/fileIOPlugin/fileIOPlugin.h
Normal file
@@ -0,0 +1,24 @@
|
||||
#ifndef FILE_IO_PLUGIN_H
|
||||
#define FILE_IO_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_fileIOPlugin(struct b3PluginContext* context);
|
||||
B3_SHARED_API void exitPlugin_fileIOPlugin(struct b3PluginContext* context);
|
||||
B3_SHARED_API int executePluginCommand_fileIOPlugin(struct b3PluginContext* context, const struct b3PluginArguments* arguments);
|
||||
|
||||
//all the APIs below are optional
|
||||
B3_SHARED_API struct CommonFileIOInterface* getFileIOFunc_fileIOPlugin(struct b3PluginContext* context);
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
};
|
||||
#endif
|
||||
|
||||
#endif //#define FILE_IO_PLUGIN_H
|
||||
@@ -182,7 +182,7 @@ void TinyRendererVisualShapeConverter::setLightSpecularCoeff(float specularCoeff
|
||||
m_data->m_hasLightSpecularCoeff = true;
|
||||
}
|
||||
|
||||
void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray<GLInstanceVertex>& verticesOut, btAlignedObjectArray<int>& indicesOut, btAlignedObjectArray<MyTexture2>& texturesOut, b3VisualShapeData& visualShapeOut)
|
||||
static void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray<GLInstanceVertex>& verticesOut, btAlignedObjectArray<int>& indicesOut, btAlignedObjectArray<MyTexture2>& texturesOut, b3VisualShapeData& visualShapeOut, struct CommonFileIOInterface* fileIO)
|
||||
{
|
||||
visualShapeOut.m_visualGeometryType = visual->m_geometry.m_type;
|
||||
visualShapeOut.m_dimensions[0] = 0;
|
||||
@@ -322,7 +322,7 @@ void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPathPrefi
|
||||
{
|
||||
//glmesh = LoadMeshFromObj(fullPath,visualPathPrefix);
|
||||
b3ImportMeshData meshData;
|
||||
if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(visual->m_geometry.m_meshFileName, meshData))
|
||||
if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(visual->m_geometry.m_meshFileName, meshData, fileIO))
|
||||
{
|
||||
if (meshData.m_textureImage1)
|
||||
{
|
||||
@@ -338,7 +338,7 @@ void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPathPrefi
|
||||
break;
|
||||
}
|
||||
case UrdfGeometry::FILE_STL:
|
||||
glmesh = LoadMeshFromSTL(visual->m_geometry.m_meshFileName.c_str());
|
||||
glmesh = LoadMeshFromSTL(visual->m_geometry.m_meshFileName.c_str(), fileIO);
|
||||
break;
|
||||
case UrdfGeometry::FILE_COLLADA:
|
||||
{
|
||||
@@ -354,7 +354,8 @@ void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPathPrefi
|
||||
visualShapeInstances,
|
||||
upAxisTrans,
|
||||
unitMeterScaling,
|
||||
upAxis);
|
||||
upAxis,
|
||||
fileIO);
|
||||
|
||||
glmesh = new GLInstanceGraphicsShape;
|
||||
// int index = 0;
|
||||
@@ -540,9 +541,10 @@ static btVector4 sColors[4] =
|
||||
};
|
||||
|
||||
void TinyRendererVisualShapeConverter::convertVisualShapes(
|
||||
int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame,
|
||||
const UrdfLink* linkPtr, const UrdfModel* model,
|
||||
int collisionObjectUniqueId, int bodyUniqueId)
|
||||
int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame,
|
||||
const UrdfLink* linkPtr, const UrdfModel* model, int collisionObjectUniqueId,
|
||||
int bodyUniqueId, struct CommonFileIOInterface* fileIO)
|
||||
|
||||
{
|
||||
btAssert(linkPtr); // TODO: remove if (not doing it now, because diff will be 50+ lines)
|
||||
if (linkPtr)
|
||||
@@ -663,7 +665,7 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(
|
||||
|
||||
{
|
||||
B3_PROFILE("convertURDFToVisualShape");
|
||||
convertURDFToVisualShape(vis, pathPrefix, localInertiaFrame.inverse() * childTrans, vertices, indices, textures, visualShape);
|
||||
convertURDFToVisualShape(vis, pathPrefix, localInertiaFrame.inverse() * childTrans, vertices, indices, textures, visualShape, fileIO);
|
||||
}
|
||||
|
||||
if (vertices.size() && indices.size())
|
||||
|
||||
@@ -11,7 +11,7 @@ struct TinyRendererVisualShapeConverter : public UrdfRenderingInterface
|
||||
|
||||
virtual ~TinyRendererVisualShapeConverter();
|
||||
|
||||
virtual void convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfLink* linkPtr, const UrdfModel* model, int shapeUid, int objectIndex);
|
||||
virtual void convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfLink* linkPtr, const UrdfModel* model, int collisionObjectUniqueId, int bodyUniqueId, struct CommonFileIOInterface* fileIO);
|
||||
|
||||
virtual int getNumVisualShapes(int bodyUniqueId);
|
||||
|
||||
|
||||
@@ -41,8 +41,7 @@ B3_SHARED_API int initPlugin_vrSyncPlugin(struct b3PluginContext* context)
|
||||
{
|
||||
MyClass* obj = new MyClass();
|
||||
context->m_userPointer = obj;
|
||||
|
||||
printf("hi vrSyncPlugin!\n");
|
||||
|
||||
return SHARED_MEMORY_MAGIC_NUMBER;
|
||||
}
|
||||
|
||||
@@ -192,6 +191,4 @@ B3_SHARED_API void exitPlugin_vrSyncPlugin(struct b3PluginContext* context)
|
||||
MyClass* obj = (MyClass*)context->m_userPointer;
|
||||
delete obj;
|
||||
context->m_userPointer = 0;
|
||||
|
||||
printf("bye vrSyncPlugin!\n");
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user