add arguments to plugin system
This commit is contained in:
@@ -32,6 +32,9 @@ SET(BulletRobotics_SRCS
|
|||||||
../../examples/SharedMemory/PhysicsDirectC_API.h
|
../../examples/SharedMemory/PhysicsDirectC_API.h
|
||||||
../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp
|
../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp
|
||||||
../../examples/SharedMemory/PhysicsServerCommandProcessor.h
|
../../examples/SharedMemory/PhysicsServerCommandProcessor.h
|
||||||
|
../../examples/SharedMemory/b3PluginManager.cpp
|
||||||
|
../../examples/SharedMemory/b3PluginManager.h
|
||||||
|
|
||||||
../../examples/SharedMemory/PhysicsClientSharedMemory.cpp
|
../../examples/SharedMemory/PhysicsClientSharedMemory.cpp
|
||||||
../../examples/SharedMemory/PhysicsClientSharedMemory.h
|
../../examples/SharedMemory/PhysicsClientSharedMemory.h
|
||||||
../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp
|
../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp
|
||||||
|
|||||||
@@ -145,7 +145,7 @@ int b3PluginManager::executePluginCommand(int pluginUniqueId, const char* argume
|
|||||||
b3PluginHandle* plugin = m_data->m_plugins.getHandle(pluginUniqueId);
|
b3PluginHandle* plugin = m_data->m_plugins.getHandle(pluginUniqueId);
|
||||||
if (plugin)
|
if (plugin)
|
||||||
{
|
{
|
||||||
result = plugin->m_executeCommandFunc();
|
result = plugin->m_executeCommandFunc(arguments);
|
||||||
}
|
}
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -12,8 +12,8 @@
|
|||||||
|
|
||||||
#if defined(_WIN32)
|
#if defined(_WIN32)
|
||||||
#define B3_API_ENTRY
|
#define B3_API_ENTRY
|
||||||
#define B3_API_CALL __stdcall
|
#define B3_API_CALL __cdecl
|
||||||
#define B3_CALLBACK __stdcall
|
#define B3_CALLBACK __cdecl
|
||||||
#else
|
#else
|
||||||
#define B3_API_ENTRY
|
#define B3_API_ENTRY
|
||||||
#define B3_API_CALL
|
#define B3_API_CALL
|
||||||
@@ -28,7 +28,7 @@ extern "C" {
|
|||||||
/* Plugin API */
|
/* Plugin API */
|
||||||
typedef B3_API_ENTRY int (B3_API_CALL * PFN_INIT)();
|
typedef B3_API_ENTRY int (B3_API_CALL * PFN_INIT)();
|
||||||
typedef B3_API_ENTRY void (B3_API_CALL * PFN_EXIT)();
|
typedef B3_API_ENTRY void (B3_API_CALL * PFN_EXIT)();
|
||||||
typedef B3_API_ENTRY int (B3_API_CALL * PFN_EXECUTE)();
|
typedef B3_API_ENTRY int (B3_API_CALL * PFN_EXECUTE)(const char* arguments);
|
||||||
|
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -10,8 +10,9 @@ B3_SHARED_API int initPlugin()
|
|||||||
return SHARED_MEMORY_MAGIC_NUMBER;
|
return SHARED_MEMORY_MAGIC_NUMBER;
|
||||||
}
|
}
|
||||||
|
|
||||||
B3_SHARED_API int executePluginCommand()
|
B3_SHARED_API int executePluginCommand(const char* arguments)
|
||||||
{
|
{
|
||||||
|
printf("arguments:%s\n",arguments);
|
||||||
return 42;
|
return 42;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -10,7 +10,7 @@ extern "C"
|
|||||||
|
|
||||||
B3_SHARED_API int initPlugin();
|
B3_SHARED_API int initPlugin();
|
||||||
B3_SHARED_API void exitPlugin();
|
B3_SHARED_API void exitPlugin();
|
||||||
B3_SHARED_API int executePluginCommand();
|
B3_SHARED_API int executePluginCommand(const char* arguments);
|
||||||
|
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -6726,6 +6726,9 @@ static PyObject* pybullet_executePluginCommand(PyObject* self,
|
|||||||
int pluginUniqueId = -1;
|
int pluginUniqueId = -1;
|
||||||
int commandUniqueId = -1;
|
int commandUniqueId = -1;
|
||||||
char* arguments = 0;
|
char* arguments = 0;
|
||||||
|
b3SharedMemoryCommandHandle command=0;
|
||||||
|
b3SharedMemoryStatusHandle statusHandle=0;
|
||||||
|
int statusType = -1;
|
||||||
|
|
||||||
b3PhysicsClientHandle sm = 0;
|
b3PhysicsClientHandle sm = 0;
|
||||||
static char* kwlist[] = { "pluginUniqueId", "commandUniqueId", "arguments", "physicsClientId", NULL };
|
static char* kwlist[] = { "pluginUniqueId", "commandUniqueId", "arguments", "physicsClientId", NULL };
|
||||||
@@ -6741,9 +6744,6 @@ static PyObject* pybullet_executePluginCommand(PyObject* self,
|
|||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
b3SharedMemoryCommandHandle command=0;
|
|
||||||
b3SharedMemoryStatusHandle statusHandle=0;
|
|
||||||
int statusType = -1;
|
|
||||||
|
|
||||||
command = b3CreateCustomCommand(sm);
|
command = b3CreateCustomCommand(sm);
|
||||||
b3CustomCommandExecutePluginCommand(command, pluginUniqueId, commandUniqueId, arguments);
|
b3CustomCommandExecutePluginCommand(command, pluginUniqueId, commandUniqueId, arguments);
|
||||||
|
|||||||
Reference in New Issue
Block a user