add option to statically link a plugin, select the postFix (to avoid naming conflict of multiple plugins functions ('initPlugin' becomes initPlugin_postFix)
pass events (keyboard, mouse, vr controllers etc) to the plugin, and clear them after the tick callback, so that it doesn't interfere with Python 'getEvents'
This commit is contained in:
@@ -1777,6 +1777,23 @@ B3_SHARED_API void b3CustomCommandLoadPlugin(b3SharedMemoryCommandHandle command
|
||||
}
|
||||
}
|
||||
|
||||
B3_SHARED_API void b3CustomCommandLoadPluginSetPostFix(b3SharedMemoryCommandHandle commandHandle, const char* postFix)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command->m_type == CMD_CUSTOM_COMMAND);
|
||||
if (command->m_type == CMD_CUSTOM_COMMAND)
|
||||
{
|
||||
command->m_updateFlags |= CMD_CUSTOM_COMMAND_LOAD_PLUGIN_POSTFIX;
|
||||
command->m_customCommandArgs.m_postFix[0] = 0;
|
||||
|
||||
int len = strlen(postFix);
|
||||
if (len<MAX_FILENAME_LENGTH)
|
||||
{
|
||||
strcpy(command->m_customCommandArgs.m_postFix, postFix);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
B3_SHARED_API int b3GetStatusPluginCommandResult(b3SharedMemoryStatusHandle statusHandle)
|
||||
|
||||
@@ -63,6 +63,7 @@ B3_SHARED_API int b3GetStatusType(b3SharedMemoryStatusHandle statusHandle);
|
||||
///Plugin system, load and unload a plugin, execute a command
|
||||
B3_SHARED_API b3SharedMemoryCommandHandle b3CreateCustomCommand(b3PhysicsClientHandle physClient);
|
||||
B3_SHARED_API void b3CustomCommandLoadPlugin(b3SharedMemoryCommandHandle commandHandle, const char* pluginPath);
|
||||
B3_SHARED_API void b3CustomCommandLoadPluginSetPostFix(b3SharedMemoryCommandHandle commandHandle, const char* postFix);
|
||||
B3_SHARED_API int b3GetStatusPluginUniqueId(b3SharedMemoryStatusHandle statusHandle);
|
||||
B3_SHARED_API int b3GetStatusPluginCommandResult(b3SharedMemoryStatusHandle statusHandle);
|
||||
|
||||
|
||||
@@ -40,6 +40,11 @@
|
||||
#include "../Utils/b3Clock.h"
|
||||
#include "b3PluginManager.h"
|
||||
|
||||
|
||||
#ifdef STATIC_LINK_VR_PLUGIN
|
||||
#include "plugins/vrSyncPlugin/vrSyncPlugin.h"
|
||||
#endif
|
||||
|
||||
#ifdef B3_ENABLE_TINY_AUDIO
|
||||
#include "../TinyAudio/b3SoundEngine.h"
|
||||
#endif
|
||||
@@ -1546,10 +1551,11 @@ struct PhysicsServerCommandProcessorInternalData
|
||||
|
||||
|
||||
{
|
||||
//test to statically link a plugin
|
||||
//#include "plugins/testPlugin/testplugin.h"
|
||||
//register static plugins:
|
||||
//m_pluginManager.registerStaticLinkedPlugin("path", initPlugin, exitPlugin, executePluginCommand);
|
||||
#ifdef STATIC_LINK_VR_PLUGIN
|
||||
m_pluginManager.registerStaticLinkedPlugin("vrSyncPlugin", initPlugin_vrSyncPlugin, exitPlugin_vrSyncPlugin, executePluginCommand_vrSyncPlugin,preTickPluginCallback_vrSyncPlugin,0);
|
||||
#endif //STATIC_LINK_VR_PLUGIN
|
||||
|
||||
}
|
||||
|
||||
m_vrControllerEvents.init();
|
||||
@@ -1699,7 +1705,6 @@ void logCallback(btDynamicsWorld *world, btScalar timeStep)
|
||||
|
||||
bool isPreTick = false;
|
||||
proc->tickPlugins(timeStep, isPreTick);
|
||||
|
||||
}
|
||||
|
||||
bool MyContactAddedCallback(btManifoldPoint& cp, const btCollisionObjectWrapper* colObj0Wrap,int partId0,int index0,const btCollisionObjectWrapper* colObj1Wrap,int partId1,int index1)
|
||||
@@ -1810,6 +1815,11 @@ void PhysicsServerCommandProcessor::processCollisionForces(btScalar timeStep)
|
||||
void PhysicsServerCommandProcessor::tickPlugins(btScalar timeStep, bool isPreTick)
|
||||
{
|
||||
m_data->m_pluginManager.tickPlugins(timeStep, isPreTick);
|
||||
if (!isPreTick)
|
||||
{
|
||||
//clear events after each postTick, so we don't receive events multiple ticks
|
||||
m_data->m_pluginManager.clearEvents();
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -8027,7 +8037,13 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
if (clientCmd.m_updateFlags & CMD_CUSTOM_COMMAND_LOAD_PLUGIN)
|
||||
{
|
||||
//pluginPath could be registered or load from disk
|
||||
int pluginUniqueId = m_data->m_pluginManager.loadPlugin(clientCmd.m_customCommandArgs.m_pluginPath);
|
||||
const char* postFix = "";
|
||||
if (clientCmd.m_updateFlags & CMD_CUSTOM_COMMAND_LOAD_PLUGIN_POSTFIX)
|
||||
{
|
||||
postFix = clientCmd.m_customCommandArgs.m_postFix;
|
||||
}
|
||||
|
||||
int pluginUniqueId = m_data->m_pluginManager.loadPlugin(clientCmd.m_customCommandArgs.m_pluginPath, postFix);
|
||||
if (pluginUniqueId>=0)
|
||||
{
|
||||
serverCmd.m_customCommandResultArgs.m_pluginUniqueId = pluginUniqueId;
|
||||
@@ -8291,7 +8307,7 @@ bool PhysicsServerCommandProcessor::isRealTimeSimulationEnabled() const
|
||||
void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec,const struct b3VRControllerEvent* vrControllerEvents, int numVRControllerEvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents, const struct b3MouseEvent* mouseEvents, int numMouseEvents)
|
||||
{
|
||||
m_data->m_vrControllerEvents.addNewVREvents(vrControllerEvents,numVRControllerEvents);
|
||||
|
||||
m_data->m_pluginManager.addEvents(vrControllerEvents, numVRControllerEvents, keyEvents, numKeyEvents, mouseEvents, numMouseEvents);
|
||||
|
||||
for (int i=0;i<m_data->m_stateLoggers.size();i++)
|
||||
{
|
||||
|
||||
@@ -114,6 +114,7 @@ enum CustomCommandEnum
|
||||
CMD_CUSTOM_COMMAND_LOAD_PLUGIN=1,
|
||||
CMD_CUSTOM_COMMAND_UNLOAD_PLUGIN=2,
|
||||
CMD_CUSTOM_COMMAND_EXECUTE_PLUGIN_COMMAND=4,
|
||||
CMD_CUSTOM_COMMAND_LOAD_PLUGIN_POSTFIX=8,
|
||||
};
|
||||
|
||||
struct b3CustomCommand
|
||||
@@ -121,6 +122,8 @@ struct b3CustomCommand
|
||||
int m_pluginUniqueId;
|
||||
b3PluginArguments m_arguments;
|
||||
char m_pluginPath[MAX_FILENAME_LENGTH];
|
||||
char m_postFix[MAX_FILENAME_LENGTH];
|
||||
|
||||
};
|
||||
|
||||
struct b3CustomCommandResultArgs
|
||||
|
||||
@@ -74,8 +74,11 @@ typedef b3PoolBodyHandle<b3Plugin> b3PluginHandle;
|
||||
struct b3PluginManagerInternalData
|
||||
{
|
||||
b3ResizablePool<b3PluginHandle> m_plugins;
|
||||
b3HashMap<b3HashString, b3PluginHandle> m_pluginMap;
|
||||
b3HashMap<b3HashString, b3PluginHandle*> m_pluginMap;
|
||||
PhysicsDirect* m_physicsDirect;
|
||||
b3AlignedObjectArray<b3KeyboardEvent> m_keyEvents;
|
||||
b3AlignedObjectArray<b3VRControllerEvent> m_vrEvents;
|
||||
b3AlignedObjectArray<b3MouseEvent> m_mouseEvents;
|
||||
};
|
||||
|
||||
b3PluginManager::b3PluginManager(class PhysicsCommandProcessorInterface* physSdk)
|
||||
@@ -89,8 +92,8 @@ b3PluginManager::~b3PluginManager()
|
||||
{
|
||||
while (m_data->m_pluginMap.size())
|
||||
{
|
||||
b3PluginHandle* plugin = m_data->m_pluginMap.getAtIndex(0);
|
||||
unloadPlugin(plugin->m_pluginUniqueId);
|
||||
b3PluginHandle** plugin = m_data->m_pluginMap.getAtIndex(0);
|
||||
unloadPlugin((*plugin)->m_pluginUniqueId);
|
||||
}
|
||||
delete m_data->m_physicsDirect;
|
||||
m_data->m_pluginMap.clear();
|
||||
@@ -98,16 +101,46 @@ b3PluginManager::~b3PluginManager()
|
||||
delete m_data;
|
||||
}
|
||||
|
||||
void b3PluginManager::addEvents(const struct b3VRControllerEvent* vrControllerEvents, int numVRControllerEvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents, const struct b3MouseEvent* mouseEvents, int numMouseEvents)
|
||||
{
|
||||
static int maxSize = 0;
|
||||
|
||||
int b3PluginManager::loadPlugin(const char* pluginPath)
|
||||
for (int i = 0; i < numKeyEvents; i++)
|
||||
{
|
||||
m_data->m_keyEvents.push_back(keyEvents[i]);
|
||||
}
|
||||
|
||||
for (int i = 0; i < numVRControllerEvents; i++)
|
||||
{
|
||||
m_data->m_vrEvents.push_back(vrControllerEvents[i]);
|
||||
if (m_data->m_vrEvents.size() > maxSize)
|
||||
{
|
||||
printf("maxSize=%d\n", maxSize);
|
||||
maxSize = m_data->m_vrEvents.size();
|
||||
}
|
||||
}
|
||||
for (int i = 0; i < numMouseEvents; i++)
|
||||
{
|
||||
m_data->m_mouseEvents.push_back(mouseEvents[i]);
|
||||
}
|
||||
}
|
||||
|
||||
void b3PluginManager::clearEvents()
|
||||
{
|
||||
m_data->m_keyEvents.resize(0);
|
||||
m_data->m_vrEvents.resize(0);
|
||||
m_data->m_mouseEvents.resize(0);
|
||||
}
|
||||
|
||||
int b3PluginManager::loadPlugin(const char* pluginPath, const char* postFixStr)
|
||||
{
|
||||
int pluginUniqueId = -1;
|
||||
|
||||
b3Plugin* pluginOrg = m_data->m_pluginMap.find(pluginPath);
|
||||
if (pluginOrg)
|
||||
b3PluginHandle** pluginOrgPtr = m_data->m_pluginMap.find(pluginPath);
|
||||
if (pluginOrgPtr)
|
||||
{
|
||||
//already loaded
|
||||
pluginUniqueId = pluginOrg->m_pluginUniqueId;
|
||||
pluginUniqueId = (*pluginOrgPtr)->m_pluginUniqueId;
|
||||
}
|
||||
else
|
||||
{
|
||||
@@ -118,12 +151,18 @@ int b3PluginManager::loadPlugin(const char* pluginPath)
|
||||
bool ok = false;
|
||||
if (pluginHandle)
|
||||
{
|
||||
std::string postFix = postFixStr;
|
||||
std::string initStr = std::string("initPlugin") + postFix;
|
||||
std::string exitStr = std::string("exitPlugin") + postFix;
|
||||
std::string executePluginCommandStr = std::string("executePluginCommand") + postFix;
|
||||
std::string preTickPluginCallbackStr = std::string("preTickPluginCallback") + postFix;
|
||||
std::string postTickPluginCallback = std::string("postTickPluginCallback") + postFix;
|
||||
|
||||
plugin->m_initFunc = (PFN_INIT)B3_DYNLIB_IMPORT(pluginHandle, "initPlugin");
|
||||
plugin->m_exitFunc = (PFN_EXIT)B3_DYNLIB_IMPORT(pluginHandle, "exitPlugin");
|
||||
plugin->m_executeCommandFunc = (PFN_EXECUTE)B3_DYNLIB_IMPORT(pluginHandle, "executePluginCommand");
|
||||
plugin->m_preTickFunc = (PFN_TICK)B3_DYNLIB_IMPORT(pluginHandle, "preTickPluginCallback");
|
||||
plugin->m_postTickFunc = (PFN_TICK)B3_DYNLIB_IMPORT(pluginHandle, "postTickPluginCallback");
|
||||
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());
|
||||
|
||||
if (plugin->m_initFunc && plugin->m_exitFunc && plugin->m_executeCommandFunc)
|
||||
{
|
||||
@@ -140,7 +179,7 @@ int b3PluginManager::loadPlugin(const char* pluginPath)
|
||||
plugin->m_ownsPluginHandle = true;
|
||||
plugin->m_pluginHandle = pluginHandle;
|
||||
plugin->m_pluginPath = pluginPath;
|
||||
m_data->m_pluginMap.insert(pluginPath, *plugin);
|
||||
m_data->m_pluginMap.insert(pluginPath, plugin);
|
||||
}
|
||||
else
|
||||
{
|
||||
@@ -190,14 +229,28 @@ void b3PluginManager::tickPlugins(double timeStep, bool isPreTick)
|
||||
{
|
||||
for (int i=0;i<m_data->m_pluginMap.size();i++)
|
||||
{
|
||||
b3PluginHandle* plugin = m_data->m_pluginMap.getAtIndex(i);
|
||||
|
||||
b3PluginHandle** pluginPtr = m_data->m_pluginMap.getAtIndex(i);
|
||||
b3PluginHandle* plugin = 0;
|
||||
if (pluginPtr && *pluginPtr)
|
||||
{
|
||||
plugin = *pluginPtr;
|
||||
}
|
||||
else
|
||||
{
|
||||
continue;
|
||||
}
|
||||
PFN_TICK tick = isPreTick? plugin->m_preTickFunc : plugin->m_postTickFunc;
|
||||
if (tick)
|
||||
{
|
||||
b3PluginContext context;
|
||||
context.m_userPointer = plugin->m_userPointer;
|
||||
context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect;
|
||||
context.m_numMouseEvents = m_data->m_mouseEvents.size();
|
||||
context.m_mouseEvents = m_data->m_mouseEvents.size() ? &m_data->m_mouseEvents[0] : 0;
|
||||
context.m_numKeyEvents = m_data->m_keyEvents.size();
|
||||
context.m_keyEvents = m_data->m_keyEvents.size() ? &m_data->m_keyEvents[0] : 0;
|
||||
context.m_numVRControllerEvents = m_data->m_vrEvents.size();
|
||||
context.m_vrControllerEvents = m_data->m_vrEvents.size()? &m_data->m_vrEvents[0]:0;
|
||||
int result = tick(&context);
|
||||
plugin->m_userPointer = context.m_userPointer;
|
||||
}
|
||||
@@ -214,7 +267,13 @@ int b3PluginManager::executePluginCommand(int pluginUniqueId, const b3PluginArgu
|
||||
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;
|
||||
|
||||
result = plugin->m_executeCommandFunc(&context, arguments);
|
||||
plugin->m_userPointer = context.m_userPointer;
|
||||
}
|
||||
@@ -242,12 +301,19 @@ int b3PluginManager::registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT
|
||||
pluginHandle->m_pluginPath = pluginPath;
|
||||
pluginHandle->m_userPointer = 0;
|
||||
|
||||
m_data->m_pluginMap.insert(pluginPath, *pluginHandle);
|
||||
m_data->m_pluginMap.insert(pluginPath, pluginHandle);
|
||||
|
||||
{
|
||||
b3PluginContext context;
|
||||
context.m_userPointer = 0;
|
||||
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;
|
||||
|
||||
int result = pluginHandle->m_initFunc(&context);
|
||||
pluginHandle->m_userPointer = context.m_userPointer;
|
||||
}
|
||||
|
||||
@@ -12,10 +12,14 @@ class b3PluginManager
|
||||
b3PluginManager(class PhysicsCommandProcessorInterface* physSdk);
|
||||
virtual ~b3PluginManager();
|
||||
|
||||
int loadPlugin(const char* pluginPath);
|
||||
int loadPlugin(const char* pluginPath, const char* postFixStr ="");
|
||||
void unloadPlugin(int pluginUniqueId);
|
||||
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);
|
||||
|
||||
};
|
||||
|
||||
@@ -5,12 +5,17 @@
|
||||
|
||||
struct b3PluginContext
|
||||
{
|
||||
|
||||
b3PhysicsClientHandle m_physClient;
|
||||
|
||||
//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;
|
||||
int m_numKeyEvents;
|
||||
const struct b3MouseEvent* m_mouseEvents;
|
||||
int m_numMouseEvents;
|
||||
};
|
||||
|
||||
|
||||
|
||||
@@ -37,7 +37,7 @@ struct MyClass
|
||||
}
|
||||
};
|
||||
|
||||
B3_SHARED_API int initPlugin(struct b3PluginContext* context)
|
||||
B3_SHARED_API int initPlugin_vrSyncPlugin(struct b3PluginContext* context)
|
||||
{
|
||||
MyClass* obj = new MyClass();
|
||||
context->m_userPointer = obj;
|
||||
@@ -47,28 +47,17 @@ B3_SHARED_API int initPlugin(struct b3PluginContext* context)
|
||||
}
|
||||
|
||||
|
||||
B3_SHARED_API int preTickPluginCallback(struct b3PluginContext* context)
|
||||
B3_SHARED_API int preTickPluginCallback_vrSyncPlugin(struct b3PluginContext* context)
|
||||
{
|
||||
MyClass* obj = (MyClass* )context->m_userPointer;
|
||||
if (obj->m_controllerId>=0)
|
||||
if (obj && obj->m_controllerId>=0)
|
||||
{
|
||||
b3SharedMemoryCommandHandle commandHandle = b3RequestVREventsCommandInit(context->m_physClient);
|
||||
int deviceTypeFilter = VR_DEVICE_CONTROLLER;
|
||||
b3VREventsSetDeviceTypeFilter(commandHandle, deviceTypeFilter);
|
||||
|
||||
b3SharedMemoryStatusHandle statusHandle = b3SubmitClientCommandAndWaitStatus(context->m_physClient, commandHandle);
|
||||
int statusType = b3GetStatusType(statusHandle);
|
||||
if (statusType == CMD_REQUEST_VR_EVENTS_DATA_COMPLETED)
|
||||
{
|
||||
struct b3VREventsData vrEvents;
|
||||
|
||||
int i = 0;
|
||||
b3GetVREventsData(context->m_physClient, &vrEvents);
|
||||
if (vrEvents.m_numControllerEvents)
|
||||
{
|
||||
for (int n=0;n<vrEvents.m_numControllerEvents;n++)
|
||||
for (int n=0;n<context->m_numVRControllerEvents;n++)
|
||||
{
|
||||
b3VRControllerEvent& event = vrEvents.m_controllerEvents[n];
|
||||
const b3VRControllerEvent& event = context->m_vrControllerEvents[n];
|
||||
if (event.m_controllerId ==obj->m_controllerId)
|
||||
{
|
||||
if (obj->m_constraintId>=0)
|
||||
@@ -171,7 +160,7 @@ B3_SHARED_API int preTickPluginCallback(struct b3PluginContext* context)
|
||||
|
||||
|
||||
|
||||
B3_SHARED_API int executePluginCommand(struct b3PluginContext* context, const struct b3PluginArguments* arguments)
|
||||
B3_SHARED_API int executePluginCommand_vrSyncPlugin(struct b3PluginContext* context, const struct b3PluginArguments* arguments)
|
||||
{
|
||||
MyClass* obj = (MyClass*) context->m_userPointer;
|
||||
if (arguments->m_numInts>=4 && arguments->m_numFloats >= 2)
|
||||
@@ -199,7 +188,7 @@ B3_SHARED_API int executePluginCommand(struct b3PluginContext* context, const st
|
||||
}
|
||||
|
||||
|
||||
B3_SHARED_API void exitPlugin(struct b3PluginContext* context)
|
||||
B3_SHARED_API void exitPlugin_vrSyncPlugin(struct b3PluginContext* context)
|
||||
{
|
||||
MyClass* obj = (MyClass*) context->m_userPointer;
|
||||
delete obj;
|
||||
|
||||
@@ -9,12 +9,12 @@ extern "C"
|
||||
#endif
|
||||
|
||||
//initPlugin, exitPlugin and executePluginCommand are required, otherwise plugin won't load
|
||||
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);
|
||||
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.
|
||||
B3_SHARED_API int preTickPluginCallback(struct b3PluginContext* context);
|
||||
B3_SHARED_API int preTickPluginCallback_vrSyncPlugin(struct b3PluginContext* context);
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -116,7 +116,9 @@ while (controllerId<0):
|
||||
|
||||
print("Using controllerId="+str(controllerId))
|
||||
|
||||
plugin = p.loadPlugin("d:/develop/bullet3/bin/pybullet_vrSyncPlugin_vs2010_x64_release.dll")
|
||||
|
||||
plugin = p.loadPlugin("d:/develop/bullet3/bin/pybullet_vrSyncPlugin_vs2010_x64_release.dll","_vrSyncPlugin")
|
||||
#plugin = p.loadPlugin("vrSyncPlugin")
|
||||
print("PluginId="+str(plugin))
|
||||
|
||||
p.executePluginCommand(plugin ,"bla", [controllerId,pr2_cid, pr2_cid2,pr2_gripper],[50,3])
|
||||
|
||||
@@ -6681,13 +6681,15 @@ static PyObject* pybullet_loadPlugin(PyObject* self,
|
||||
int physicsClientId = 0;
|
||||
|
||||
char* pluginPath = 0;
|
||||
char* postFix = 0;
|
||||
|
||||
b3SharedMemoryCommandHandle command = 0;
|
||||
b3SharedMemoryStatusHandle statusHandle = 0;
|
||||
int statusType = -1;
|
||||
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
static char* kwlist[] = { "pluginPath", "physicsClientId", NULL };
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|i", kwlist, &pluginPath, &physicsClientId))
|
||||
static char* kwlist[] = { "pluginPath", "postFix", "physicsClientId", NULL };
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|si", kwlist, &pluginPath, &postFix, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@@ -6701,6 +6703,10 @@ static PyObject* pybullet_loadPlugin(PyObject* self,
|
||||
|
||||
command = b3CreateCustomCommand(sm);
|
||||
b3CustomCommandLoadPlugin(command, pluginPath);
|
||||
if (postFix)
|
||||
{
|
||||
b3CustomCommandLoadPluginSetPostFix(command, postFix);
|
||||
}
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
||||
statusType = b3GetStatusPluginUniqueId(statusHandle);
|
||||
return PyInt_FromLong(statusType);
|
||||
|
||||
Reference in New Issue
Block a user