create a C/C++ plugin system for pybullet / C-API.

This commit is contained in:
Erwin Coumans
2017-09-22 19:17:57 -07:00
parent b9b1b2dbca
commit 3783dccaa3
28 changed files with 1111 additions and 524 deletions

View File

@@ -171,6 +171,7 @@ SET(BulletExampleBrowser_SRCS
../SharedMemory/PhysicsServerCommandProcessor.h
../SharedMemory/SharedMemoryCommands.h
../SharedMemory/SharedMemoryPublic.h
../SharedMemory/b3PluginManager.cpp
../RobotSimulator/b3RobotSimulatorClientAPI.cpp
../RobotSimulator/b3RobotSimulatorClientAPI.h
../BasicDemo/BasicExample.cpp

View File

@@ -109,6 +109,7 @@ project "App_BulletExampleBrowser"
"../SharedMemory/PhysicsLoopBackC_API.h",
"../SharedMemory/PhysicsServerCommandProcessor.cpp",
"../SharedMemory/PhysicsServerCommandProcessor.h",
"../SharedMemory/b3PluginManager.cpp",
"../SharedMemory/TinyRendererVisualShapeConverter.cpp",
"../SharedMemory/TinyRendererVisualShapeConverter.h",
"../SharedMemory/SharedMemoryCommands.h",

View File

@@ -42,6 +42,8 @@ SET(RobotSimulator_SRCS
../../examples/SharedMemory/PhysicsDirectC_API.h
../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp
../../examples/SharedMemory/PhysicsServerCommandProcessor.h
../../examples/SharedMemory/b3PluginManager.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory.h
../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp

View File

@@ -20,6 +20,8 @@ myfiles =
"../../examples/SharedMemory/PhysicsDirectC_API.h",
"../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp",
"../../examples/SharedMemory/PhysicsServerCommandProcessor.h",
"../../examples/SharedMemory/b3PluginManager.cpp",
"../../examples/SharedMemory/PhysicsClientSharedMemory.cpp",
"../../examples/SharedMemory/PhysicsClientSharedMemory.h",
"../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp",

View File

@@ -41,6 +41,7 @@ SET(SharedMemory_SRCS
TinyRendererVisualShapeConverter.h
SharedMemoryCommands.h
SharedMemoryPublic.h
b3PluginManager.cpp
../TinyRenderer/geometry.cpp
../TinyRenderer/model.cpp
../TinyRenderer/tgaimage.cpp

View File

@@ -1631,6 +1631,7 @@ B3_SHARED_API int b3SubmitClientCommand(b3PhysicsClientHandle physClient, const
#include "../Utils/b3Clock.h"
B3_SHARED_API b3SharedMemoryStatusHandle b3SubmitClientCommandAndWaitStatus(b3PhysicsClientHandle physClient, const b3SharedMemoryCommandHandle commandHandle)
{
B3_PROFILE("b3SubmitClientCommandAndWaitStatus");
@@ -1733,6 +1734,100 @@ B3_SHARED_API int b3GetJointInfo(b3PhysicsClientHandle physClient, int bodyIndex
return cl->getJointInfo(bodyIndex, jointIndex, *info);
}
B3_SHARED_API b3SharedMemoryCommandHandle b3CreateCustomCommand(b3PhysicsClientHandle physClient)
{
PhysicsClient* cl = (PhysicsClient*)physClient;
b3Assert(cl);
b3Assert(cl->canSubmitCommand());
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command);
command->m_type = CMD_CUSTOM_COMMAND;
command->m_updateFlags = 0;
return (b3SharedMemoryCommandHandle)command;
}
B3_SHARED_API void b3CustomCommandLoadPlugin(b3SharedMemoryCommandHandle commandHandle, const char* pluginPath, int options)
{
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;
command->m_customCommandArgs.m_pluginPath[0] = 0;
command->m_customCommandArgs.m_options = options;
int len = strlen(pluginPath);
if (len<MAX_FILENAME_LENGTH)
{
strcpy(command->m_customCommandArgs.m_pluginPath, pluginPath);
}
}
}
B3_SHARED_API int b3GetStatusPluginCommandResult(b3SharedMemoryStatusHandle statusHandle)
{
int statusUniqueId = -1;
const SharedMemoryStatus* status = (const SharedMemoryStatus*)statusHandle;
b3Assert(status);
b3Assert(status->m_type == CMD_CUSTOM_COMMAND_COMPLETED);
if (status->m_type == CMD_CUSTOM_COMMAND_COMPLETED)
{
statusUniqueId = status->m_customCommandResultArgs.m_executeCommandResult;
}
return statusUniqueId;
}
B3_SHARED_API int b3GetStatusPluginUniqueId(b3SharedMemoryStatusHandle statusHandle)
{
int statusUniqueId = -1;
const SharedMemoryStatus* status = (const SharedMemoryStatus*)statusHandle;
b3Assert(status);
b3Assert(status->m_type == CMD_CUSTOM_COMMAND_COMPLETED);
if (status->m_type == CMD_CUSTOM_COMMAND_COMPLETED)
{
statusUniqueId = status->m_customCommandResultArgs.m_pluginUniqueId;
}
return statusUniqueId;
}
B3_SHARED_API void b3CustomCommandUnloadPlugin(b3SharedMemoryCommandHandle commandHandle, int pluginUniqueId)
{
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_UNLOAD_PLUGIN;
command->m_customCommandArgs.m_pluginUniqueId = pluginUniqueId;
}
}
B3_SHARED_API void b3CustomCommandExecutePluginCommand(b3SharedMemoryCommandHandle commandHandle, int pluginUniqueId, int commandUniqueId, const char* arguments)
{
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_EXECUTE_PLUGIN_COMMAND;
command->m_customCommandArgs.m_pluginUniqueId = pluginUniqueId;
command->m_customCommandArgs.m_commandUniqueId = commandUniqueId;
command->m_customCommandArgs.m_pluginArguments[0] = 0;
int len = strlen(arguments);
if (len<MAX_FILENAME_LENGTH)
{
strcpy(command->m_customCommandArgs.m_pluginArguments, arguments);
}
}
}
B3_SHARED_API b3SharedMemoryCommandHandle b3GetDynamicsInfoCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, int linkIndex)
{
PhysicsClient* cl = (PhysicsClient* ) physClient;

View File

@@ -60,6 +60,15 @@ B3_SHARED_API b3SharedMemoryStatusHandle b3ProcessServerStatus(b3PhysicsClientHa
/// Get the physics server return status type. See EnumSharedMemoryServerStatus in SharedMemoryPublic.h for error codes.
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, int options);
B3_SHARED_API int b3GetStatusPluginUniqueId(b3SharedMemoryStatusHandle statusHandle);
B3_SHARED_API int b3GetStatusPluginCommandResult(b3SharedMemoryStatusHandle statusHandle);
B3_SHARED_API void b3CustomCommandUnloadPlugin(b3SharedMemoryCommandHandle commandHandle, int pluginUniqueId);
B3_SHARED_API void b3CustomCommandExecutePluginCommand(b3SharedMemoryCommandHandle commandHandle, int pluginUniqueId, int commandUniqueId, const char* arguments);
B3_SHARED_API int b3GetStatusBodyIndices(b3SharedMemoryStatusHandle statusHandle, int* bodyIndicesOut, int bodyIndicesCapacity);
B3_SHARED_API int b3GetStatusBodyIndex(b3SharedMemoryStatusHandle statusHandle);

View File

@@ -1200,6 +1200,15 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
b3Warning("Request getCollisionInfo failed");
break;
}
case CMD_CUSTOM_COMMAND_COMPLETED:
{
break;
}
case CMD_CUSTOM_COMMAND_FAILED:
{
b3Warning("custom plugin command failed");
break;
}
default: {
b3Error("Unknown server status %d\n", serverCmd.m_type);

View File

@@ -940,6 +940,16 @@ void PhysicsDirect::postProcessStatus(const struct SharedMemoryStatus& serverCmd
break;
}
case CMD_CUSTOM_COMMAND_COMPLETED:
{
break;
}
case CMD_CUSTOM_COMMAND_FAILED:
{
b3Warning("custom plugin command failed");
break;
}
default:
{
//b3Warning("Unknown server status type");

View File

@@ -37,6 +37,8 @@
#include "LinearMath/btRandom.h"
#include "Bullet3Common/b3ResizablePool.h"
#include "../Utils/b3Clock.h"
#include "b3PluginManager.h"
#ifdef B3_ENABLE_TINY_AUDIO
#include "../TinyAudio/b3SoundEngine.h"
#endif
@@ -1430,6 +1432,8 @@ struct PhysicsServerCommandProcessorInternalData
b3ResizablePool< InternalBodyHandle > m_bodyHandles;
b3ResizablePool<InternalCollisionShapeHandle> m_userCollisionShapeHandles;
b3PluginManager m_pluginManager;
bool m_allowRealTimeSimulation;
@@ -7968,6 +7972,38 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
break;
}
case CMD_CUSTOM_COMMAND:
{
SharedMemoryStatus& serverCmd = serverStatusOut;
serverCmd.m_type = CMD_CUSTOM_COMMAND_FAILED;
serverCmd.m_customCommandResultArgs.m_pluginUniqueId = -1;
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);
if (pluginUniqueId>=0)
{
serverCmd.m_customCommandResultArgs.m_pluginUniqueId = pluginUniqueId;
serverCmd.m_type = CMD_CUSTOM_COMMAND_COMPLETED;
}
}
if (clientCmd.m_updateFlags & CMD_CUSTOM_COMMAND_UNLOAD_PLUGIN)
{
m_data->m_pluginManager.unloadPlugin(clientCmd.m_customCommandArgs.m_pluginUniqueId);
serverCmd.m_type = CMD_CUSTOM_COMMAND_COMPLETED;
}
if (clientCmd.m_updateFlags & CMD_CUSTOM_COMMAND_EXECUTE_PLUGIN_COMMAND)
{
int result = m_data->m_pluginManager.executePluginCommand(clientCmd.m_customCommandArgs.m_pluginUniqueId, clientCmd.m_customCommandArgs.m_pluginArguments);
serverCmd.m_customCommandResultArgs.m_executeCommandResult = result;
serverCmd.m_type = CMD_CUSTOM_COMMAND_COMPLETED;
}
hasStatus = true;
break;
}
default:
{
BT_PROFILE("CMD_UNKNOWN");
@@ -8186,12 +8222,6 @@ void PhysicsServerCommandProcessor::replayFromLogFile(const char* fileName)
}
btVector3 gVRGripperPos(0.7, 0.3, 0.7);
btQuaternion gVRGripperOrn(0,0,0,1);
btVector3 gVRController2Pos(0,0,0.2);
btQuaternion gVRController2Orn(0,0,0,1);
btScalar gVRGripper2Analog = 0;
btScalar gVRGripperAnalog = 0;

View File

@@ -109,6 +109,28 @@ struct b3SearchPathfArgs
char m_path[MAX_FILENAME_LENGTH];
};
enum CustomCommandEnum
{
CMD_CUSTOM_COMMAND_LOAD_PLUGIN=1,
CMD_CUSTOM_COMMAND_UNLOAD_PLUGIN=2,
CMD_CUSTOM_COMMAND_EXECUTE_PLUGIN_COMMAND=4,
};
struct b3CustomCommand
{
int m_pluginUniqueId;
int m_commandUniqueId;
int m_options;
char m_pluginPath[MAX_FILENAME_LENGTH];
char m_pluginArguments[MAX_FILENAME_LENGTH];
};
struct b3CustomCommandResultArgs
{
int m_pluginUniqueId;
int m_executeCommandResult;
};
struct BulletDataStreamArgs
{
@@ -968,6 +990,7 @@ struct SharedMemoryCommand
struct b3RequestCollisionInfoArgs m_requestCollisionInfoArgs;
struct b3ChangeTextureArgs m_changeTextureArgs;
struct b3SearchPathfArgs m_searchPathArgs;
struct b3CustomCommand m_customCommandArgs;
};
};
@@ -1039,6 +1062,7 @@ struct SharedMemoryStatus
struct b3SendCollisionInfoArgs m_sendCollisionInfoArgs;
struct SendMouseEvents m_sendMouseEvents;
struct b3LoadTextureResultArgs m_loadTextureResultArguments;
struct b3CustomCommandResultArgs m_customCommandResultArgs;
};
};

View File

@@ -72,6 +72,7 @@ enum EnumSharedMemoryClientCommand
CMD_REQUEST_MOUSE_EVENTS_DATA,
CMD_CHANGE_TEXTURE,
CMD_SET_ADDITIONAL_SEARCH_PATH,
CMD_CUSTOM_COMMAND,
//don't go beyond this command!
CMD_MAX_CLIENT_COMMANDS,
@@ -167,6 +168,9 @@ enum EnumSharedMemoryServerStatus
CMD_REQUEST_COLLISION_INFO_FAILED,
CMD_REQUEST_MOUSE_EVENTS_DATA_COMPLETED,
CMD_CHANGE_TEXTURE_COMMAND_FAILED,
CMD_CUSTOM_COMMAND_COMPLETED,
CMD_CUSTOM_COMMAND_FAILED,
//don't go beyond 'CMD_MAX_SERVER_COMMANDS!
CMD_MAX_SERVER_COMMANDS
};

View File

@@ -0,0 +1,151 @@
#include "b3PluginManager.h"
#include "Bullet3Common/b3HashMap.h"
#include "Bullet3Common/b3ResizablePool.h"
#include "plugins/b3PluginAPI.h"
#include "SharedMemoryPublic.h"
#ifdef _WIN32
#define WIN32_LEAN_AND_MEAN
#define VC_EXTRALEAN
#include <windows.h>
typedef HMODULE B3_DYNLIB_HANDLE;
#define B3_DYNLIB_OPEN LoadLibrary
#define B3_DYNLIB_CLOSE FreeLibrary
#define B3_DYNLIB_IMPORT GetProcAddress
#else
#include <dlfcn.h>
typedef void* B3_DYNLIB_HANDLE;
#define B3_DYNLIB_OPEN(path) dlopen(path, RTLD_NOW | RTLD_GLOBAL)
#define B3_DYNLIB_CLOSE dlclose
#define B3_DYNLIB_IMPORT dlsym
#endif
struct b3Plugin
{
B3_DYNLIB_HANDLE m_pluginHandle;
std::string m_pluginPath;
PFN_INIT m_initFunc;
PFN_EXIT m_exitFunc;
PFN_EXECUTE m_executeCommandFunc;
void clear()
{
B3_DYNLIB_CLOSE(m_pluginHandle);
m_pluginHandle = 0;
m_initFunc = 0;
m_exitFunc = 0;
m_executeCommandFunc = 0;
}
};
typedef b3PoolBodyHandle<b3Plugin> b3PluginHandle;
struct b3PluginManagerInternalData
{
b3ResizablePool<b3PluginHandle> m_plugins;
b3HashMap<b3HashString, b3PluginHandle> m_pluginMap;
};
b3PluginManager::b3PluginManager()
{
m_data = new b3PluginManagerInternalData;
}
b3PluginManager::~b3PluginManager()
{
m_data->m_pluginMap.clear();
m_data->m_plugins.exitHandles();
delete m_data;
}
int b3PluginManager::loadPlugin(const char* pluginPath)
{
int pluginUniqueId = -1;
b3Plugin* plugin = m_data->m_pluginMap.find(pluginPath);
if (plugin)
{
//already loaded
}
else
{
pluginUniqueId = m_data->m_plugins.allocHandle();
b3PluginHandle* plugin = m_data->m_plugins.getHandle(pluginUniqueId);
B3_DYNLIB_HANDLE pluginHandle = B3_DYNLIB_OPEN(pluginPath);
bool ok = false;
if (pluginHandle)
{
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");
if (plugin->m_initFunc && plugin->m_exitFunc && plugin->m_executeCommandFunc)
{
int version = plugin->m_initFunc();
if (version == SHARED_MEMORY_MAGIC_NUMBER)
{
ok = true;
plugin->m_pluginHandle = pluginHandle;
plugin->m_pluginPath = pluginPath;
m_data->m_pluginMap.insert(pluginPath, *plugin);
}
else
{
int expect = SHARED_MEMORY_MAGIC_NUMBER;
b3Warning("Warning: plugin is wrong version: expected %d, got %d\n", expect, version);
}
}
else
{
b3Warning("Loaded plugin but couldn't bind functions");
}
if (!ok)
{
B3_DYNLIB_CLOSE(pluginHandle);
}
}
else
{
b3Warning("Warning: couldn't load plugin %s\n", pluginPath);
}
if (!ok)
{
m_data->m_plugins.freeHandle(pluginUniqueId);
pluginUniqueId = -1;
}
}
return pluginUniqueId;
}
void b3PluginManager::unloadPlugin(int pluginUniqueId)
{
b3PluginHandle* plugin = m_data->m_plugins.getHandle(pluginUniqueId);
if (plugin)
{
plugin->m_exitFunc();
m_data->m_pluginMap.remove(plugin->m_pluginPath.c_str());
m_data->m_plugins.freeHandle(pluginUniqueId);
}
}
int b3PluginManager::executePluginCommand(int pluginUniqueId, const char* arguments)
{
int result = -1;
b3PluginHandle* plugin = m_data->m_plugins.getHandle(pluginUniqueId);
if (plugin)
{
result = plugin->m_executeCommandFunc();
}
return result;
}

View File

@@ -0,0 +1,19 @@
#ifndef B3_PLUGIN_MANAGER_H
#define B3_PLUGIN_MANAGER_H
class b3PluginManager
{
struct b3PluginManagerInternalData* m_data;
public:
b3PluginManager();
virtual ~b3PluginManager();
int loadPlugin(const char* pluginPath);
void unloadPlugin(int pluginUniqueId);
int executePluginCommand(int pluginUniqueId, const char* arguments);
};
#endif //B3_PLUGIN_MANAGER_H

View File

@@ -0,0 +1,37 @@
#ifndef B3_PLUGIN_API_H
#define B3_PLUGIN_API_H
#ifdef _WIN32
#define B3_SHARED_API __declspec(dllexport)
#elif defined (__GNUC__)
#define B3_SHARED_API __attribute__((visibility("default")))
#else
#define B3_SHARED_API
#endif
#if defined(_WIN32)
#define B3_API_ENTRY
#define B3_API_CALL __stdcall
#define B3_CALLBACK __stdcall
#else
#define B3_API_ENTRY
#define B3_API_CALL
#define B3_CALLBACK
#endif
#ifdef __cplusplus
extern "C" {
#endif
/* Plugin API */
typedef B3_API_ENTRY int (B3_API_CALL * PFN_INIT)();
typedef B3_API_ENTRY void (B3_API_CALL * PFN_EXIT)();
typedef B3_API_ENTRY int (B3_API_CALL * PFN_EXECUTE)();
#ifdef __cplusplus
}
#endif
#endif //B3_PLUGIN_API_H

View File

@@ -0,0 +1,42 @@
project ("pybullet_testplugin")
language "C++"
kind "SharedLib"
includedirs {".","../../../../src", "../../../../examples",
"../../../ThirdPartyLibs"}
defines {"PHYSICS_IN_PROCESS_EXAMPLE_BROWSER"}
hasCL = findOpenCL("clew")
links{"BulletFileLoader", "Bullet3Common", "LinearMath"}
if os.is("MacOSX") then
-- targetextension {"so"}
links{"Cocoa.framework","Python"}
end
files {
"testplugin.cpp",
"../../PhysicsClient.cpp",
"../../PhysicsClient.h",
"../../PhysicsClientSharedMemory.cpp",
"../../PhysicsClientSharedMemory.h",
"../../PhysicsClientSharedMemory_C_API.cpp",
"../../PhysicsClientSharedMemory_C_API.h",
"../../PhysicsClientC_API.cpp",
"../../PhysicsClientC_API.h",
"../../Win32SharedMemory.cpp",
"../../Win32SharedMemory.h",
"../../PosixSharedMemory.cpp",
"../../PosixSharedMemory.h",
"../../../Utils/b3Clock.cpp",
"../../../Utils/b3Clock.h",
"../../../Utils/b3ResourcePath.cpp",
"../../../Utils/b3ResourcePath.h",
}

View File

@@ -0,0 +1,22 @@
#include "testplugin.h"
#include "../../SharedMemoryPublic.h"
#include <stdio.h>
B3_SHARED_API int initPlugin()
{
printf("hi!\n");
return SHARED_MEMORY_MAGIC_NUMBER;
}
B3_SHARED_API int executePluginCommand()
{
return 42;
}
B3_SHARED_API void exitPlugin()
{
printf("bye!\n");
}

View File

@@ -0,0 +1,19 @@
#ifndef TEST_PLUGIN_H
#define TEST_PLUGIN_H
#include "../b3PluginAPI.h"
#ifdef __cplusplus
extern "C"
{
#endif
B3_SHARED_API int initPlugin();
B3_SHARED_API void exitPlugin();
B3_SHARED_API int executePluginCommand();
#ifdef __cplusplus
};
#endif
#endif//#define TEST_PLUGIN_H

View File

@@ -7,7 +7,7 @@ else
kind "ConsoleApp"
end
includedirs {".","../../src", "../ThirdPartyLibs",}
includedirs {".","../../src", "../ThirdPartyLibs"}
links {
"Bullet3Common","BulletInverseDynamicsUtils", "BulletInverseDynamics", "BulletDynamics","BulletCollision", "LinearMath", "BussIK"
@@ -53,6 +53,8 @@ myfiles =
"SharedMemoryCommandProcessor.h",
"PhysicsServerCommandProcessor.cpp",
"PhysicsServerCommandProcessor.h",
"b3PluginManager.cpp",
"b3PluginManager.h",
"TinyRendererVisualShapeConverter.cpp",
"TinyRendererVisualShapeConverter.h",
"../TinyRenderer/geometry.cpp",
@@ -99,6 +101,7 @@ myfiles =
"../ThirdPartyLibs/tinyxml/tinyxmlparser.cpp",
"../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp",
"../ThirdPartyLibs/stb_image/stb_image.cpp",
}
files {
@@ -405,4 +408,4 @@ end
include "udp"
include "tcp"
include "plugins/testPlugin"

View File

@@ -88,6 +88,7 @@ myfiles =
"../SharedMemoryPublic.h",
"../PhysicsServerCommandProcessor.cpp",
"../PhysicsServerCommandProcessor.h",
"../b3PluginManager.cpp",
"../TinyRendererVisualShapeConverter.cpp",
"../TinyRendererVisualShapeConverter.h",
"../../TinyRenderer/geometry.cpp",

View File

@@ -79,6 +79,7 @@ myfiles =
"../SharedMemoryPublic.h",
"../PhysicsServerCommandProcessor.cpp",
"../PhysicsServerCommandProcessor.h",
"../b3PluginManager.cpp",
"../TinyRendererVisualShapeConverter.cpp",
"../TinyRendererVisualShapeConverter.h",
"../../TinyRenderer/geometry.cpp",

View File

@@ -43,6 +43,9 @@ SET(pybullet_SRCS
../../examples/SharedMemory/PhysicsDirectC_API.h
../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp
../../examples/SharedMemory/PhysicsServerCommandProcessor.h
../../examples/SharedMemory/b3PluginManager.cpp
../../examples/SharedMemory/b3PluginManager.h
../../examples/SharedMemory/PhysicsClientSharedMemory.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory.h
../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp

View File

@@ -116,6 +116,8 @@ if not _OPTIONS["no-enet"] then
"../../examples/SharedMemory/PhysicsDirectC_API.h",
"../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp",
"../../examples/SharedMemory/PhysicsServerCommandProcessor.h",
"../../examples/SharedMemory/b3PluginManager.cpp",
"../../examples/SharedMemory/b3PluginManager.h",
"../../examples/SharedMemory/PhysicsClientSharedMemory.cpp",
"../../examples/SharedMemory/PhysicsClientSharedMemory.h",
"../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp",

View File

@@ -6653,6 +6653,108 @@ static PyObject* pybullet_getEulerFromQuaternion(PyObject* self,
return Py_None;
}
static PyObject* pybullet_loadPlugin(PyObject* self,
PyObject* args, PyObject* keywds)
{
int physicsClientId = 0;
int option = 0;
char* pluginPath = 0;
b3SharedMemoryCommandHandle command = 0;
b3SharedMemoryStatusHandle statusHandle = 0;
int statusType = -1;
b3PhysicsClientHandle sm = 0;
static char* kwlist[] = { "pluginPath", "option", "physicsClientId", NULL };
if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|ii", kwlist, &pluginPath, &option, &physicsClientId))
{
return NULL;
}
sm = getPhysicsClient(physicsClientId);
if (sm == 0)
{
PyErr_SetString(SpamError, "Not connected to physics server.");
return NULL;
}
command = b3CreateCustomCommand(sm);
b3CustomCommandLoadPlugin(command, pluginPath, option);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
statusType = b3GetStatusPluginUniqueId(statusHandle);
return PyInt_FromLong(statusType);
}
static PyObject* pybullet_unloadPlugin(PyObject* self,
PyObject* args, PyObject* keywds)
{
int physicsClientId = 0;
int pluginUniqueId = -1;
b3SharedMemoryCommandHandle command = 0;
b3SharedMemoryStatusHandle statusHandle = 0;
int statusType = -1;
b3PhysicsClientHandle sm = 0;
static char* kwlist[] = { "pluginUniqueId", "physicsClientId", NULL };
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist, &pluginUniqueId,&physicsClientId))
{
return NULL;
}
sm = getPhysicsClient(physicsClientId);
if (sm == 0)
{
PyErr_SetString(SpamError, "Not connected to physics server.");
return NULL;
}
command = b3CreateCustomCommand(sm);
b3CustomCommandUnloadPlugin(command, pluginUniqueId);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
Py_INCREF(Py_None);
return Py_None;;
}
//createCustomCommand for executing commands implemented in a plugin system
static PyObject* pybullet_executePluginCommand(PyObject* self,
PyObject* args, PyObject* keywds)
{
int physicsClientId = 0;
int pluginUniqueId = -1;
int commandUniqueId = -1;
char* arguments = 0;
b3PhysicsClientHandle sm = 0;
static char* kwlist[] = { "pluginUniqueId", "commandUniqueId", "arguments", "physicsClientId", NULL };
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|si", kwlist, &pluginUniqueId, &commandUniqueId, &arguments, &physicsClientId))
{
return NULL;
}
sm = getPhysicsClient(physicsClientId);
if (sm == 0)
{
PyErr_SetString(SpamError, "Not connected to physics server.");
return NULL;
}
b3SharedMemoryCommandHandle command=0;
b3SharedMemoryStatusHandle statusHandle=0;
int statusType = -1;
command = b3CreateCustomCommand(sm);
b3CustomCommandExecutePluginCommand(command, pluginUniqueId, commandUniqueId, arguments);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
statusType = b3GetStatusPluginCommandResult(statusHandle);
return PyInt_FromLong(statusType);
}
///Inverse Kinematics binding
static PyObject* pybullet_calculateInverseKinematics(PyObject* self,
PyObject* args, PyObject* keywds)
@@ -6947,6 +7049,7 @@ static PyObject* pybullet_calculateInverseDynamics(PyObject* self,
return Py_None;
}
static PyMethodDef SpamMethods[] = {
{"connect", (PyCFunction)pybullet_connectPhysicsServer, METH_VARARGS | METH_KEYWORDS,
@@ -7265,6 +7368,16 @@ static PyMethodDef SpamMethods[] = {
"Cast a batch of rays and return the result for each of the rays (first object hit, if any. or -1) "
"Takes two arguments (list of from_positions [x,y,z] and a list of to_positions [x,y,z] in Cartesian world coordinates"},
{ "loadPlugin", (PyCFunction)pybullet_loadPlugin, METH_VARARGS | METH_KEYWORDS,
"Load a plugin, could implement custom commands etc." },
{ "unloadPlugin", (PyCFunction)pybullet_unloadPlugin, METH_VARARGS | METH_KEYWORDS,
"Unload a plugin, given the pluginUniqueId." },
{ "executePluginCommand", (PyCFunction)pybullet_executePluginCommand, METH_VARARGS | METH_KEYWORDS,
"Execute a command, implemented in a plugin." },
{"submitProfileTiming", (PyCFunction)pybullet_submitProfileTiming, METH_VARARGS | METH_KEYWORDS,
"Add a custom profile timing that will be visible in performance profile recordings on the physics server."
"On the physics server (in GUI and VR mode) you can press 'p' to start and/or stop profile recordings" },

File diff suppressed because it is too large Load Diff