More work on the C/C++ plugin system for pybullet/C-API:
Add preTickPluginCallback/postTickPluginCallback User pointer for b3PluginContext, to store objects (class/struct instances) Pass ints and floats as optional argument for plugin executePluginCommand
This commit is contained in:
@@ -1748,7 +1748,7 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3CreateCustomCommand(b3PhysicsClientH
|
|||||||
return (b3SharedMemoryCommandHandle)command;
|
return (b3SharedMemoryCommandHandle)command;
|
||||||
}
|
}
|
||||||
|
|
||||||
B3_SHARED_API void b3CustomCommandLoadPlugin(b3SharedMemoryCommandHandle commandHandle, const char* pluginPath, int options)
|
B3_SHARED_API void b3CustomCommandLoadPlugin(b3SharedMemoryCommandHandle commandHandle, const char* pluginPath)
|
||||||
{
|
{
|
||||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||||
b3Assert(command->m_type == CMD_CUSTOM_COMMAND);
|
b3Assert(command->m_type == CMD_CUSTOM_COMMAND);
|
||||||
@@ -1756,7 +1756,7 @@ B3_SHARED_API void b3CustomCommandLoadPlugin(b3SharedMemoryCommandHandle command
|
|||||||
{
|
{
|
||||||
command->m_updateFlags |= CMD_CUSTOM_COMMAND_LOAD_PLUGIN;
|
command->m_updateFlags |= CMD_CUSTOM_COMMAND_LOAD_PLUGIN;
|
||||||
command->m_customCommandArgs.m_pluginPath[0] = 0;
|
command->m_customCommandArgs.m_pluginPath[0] = 0;
|
||||||
command->m_customCommandArgs.m_options = options;
|
|
||||||
int len = strlen(pluginPath);
|
int len = strlen(pluginPath);
|
||||||
if (len<MAX_FILENAME_LENGTH)
|
if (len<MAX_FILENAME_LENGTH)
|
||||||
{
|
{
|
||||||
@@ -1806,7 +1806,7 @@ B3_SHARED_API void b3CustomCommandUnloadPlugin(b3SharedMemoryCommandHandle comma
|
|||||||
command->m_customCommandArgs.m_pluginUniqueId = pluginUniqueId;
|
command->m_customCommandArgs.m_pluginUniqueId = pluginUniqueId;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
B3_SHARED_API void b3CustomCommandExecutePluginCommand(b3SharedMemoryCommandHandle commandHandle, int pluginUniqueId, int commandUniqueId, const char* arguments)
|
B3_SHARED_API void b3CustomCommandExecutePluginCommand(b3SharedMemoryCommandHandle commandHandle, int pluginUniqueId, const char* textArguments)
|
||||||
{
|
{
|
||||||
|
|
||||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||||
@@ -1815,17 +1815,54 @@ B3_SHARED_API void b3CustomCommandExecutePluginCommand(b3SharedMemoryCommandHand
|
|||||||
{
|
{
|
||||||
command->m_updateFlags |= CMD_CUSTOM_COMMAND_EXECUTE_PLUGIN_COMMAND;
|
command->m_updateFlags |= CMD_CUSTOM_COMMAND_EXECUTE_PLUGIN_COMMAND;
|
||||||
command->m_customCommandArgs.m_pluginUniqueId = pluginUniqueId;
|
command->m_customCommandArgs.m_pluginUniqueId = pluginUniqueId;
|
||||||
command->m_customCommandArgs.m_commandUniqueId = commandUniqueId;
|
|
||||||
command->m_customCommandArgs.m_pluginArguments[0] = 0;
|
command->m_customCommandArgs.m_arguments.m_numInts = 0;
|
||||||
int len = strlen(arguments);
|
command->m_customCommandArgs.m_arguments.m_numFloats = 0;
|
||||||
|
command->m_customCommandArgs.m_arguments.m_text[0] = 0;
|
||||||
|
|
||||||
|
int len = strlen(textArguments);
|
||||||
|
|
||||||
if (len<MAX_FILENAME_LENGTH)
|
if (len<MAX_FILENAME_LENGTH)
|
||||||
{
|
{
|
||||||
strcpy(command->m_customCommandArgs.m_pluginArguments, arguments);
|
strcpy(command->m_customCommandArgs.m_arguments.m_text, textArguments);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
B3_SHARED_API void b3CustomCommandExecuteAddIntArgument(b3SharedMemoryCommandHandle commandHandle, int intVal)
|
||||||
|
{
|
||||||
|
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||||
|
b3Assert(command->m_type == CMD_CUSTOM_COMMAND);
|
||||||
|
b3Assert(command->m_updateFlags & CMD_CUSTOM_COMMAND_EXECUTE_PLUGIN_COMMAND);
|
||||||
|
if (command->m_type == CMD_CUSTOM_COMMAND && (command->m_updateFlags & CMD_CUSTOM_COMMAND_EXECUTE_PLUGIN_COMMAND))
|
||||||
|
{
|
||||||
|
int numInts = command->m_customCommandArgs.m_arguments.m_numInts;
|
||||||
|
if (numInts<B3_MAX_PLUGIN_ARG_SIZE)
|
||||||
|
{
|
||||||
|
command->m_customCommandArgs.m_arguments.m_ints[numInts]=intVal;
|
||||||
|
command->m_customCommandArgs.m_arguments.m_numInts++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
B3_SHARED_API void b3CustomCommandExecuteAddFloatArgument(b3SharedMemoryCommandHandle commandHandle, float floatVal)
|
||||||
|
{
|
||||||
|
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||||
|
b3Assert(command->m_type == CMD_CUSTOM_COMMAND);
|
||||||
|
b3Assert(command->m_updateFlags & CMD_CUSTOM_COMMAND_EXECUTE_PLUGIN_COMMAND);
|
||||||
|
if (command->m_type == CMD_CUSTOM_COMMAND && (command->m_updateFlags & CMD_CUSTOM_COMMAND_EXECUTE_PLUGIN_COMMAND))
|
||||||
|
{
|
||||||
|
int numFloats = command->m_customCommandArgs.m_arguments.m_numFloats;
|
||||||
|
if (numFloats<B3_MAX_PLUGIN_ARG_SIZE)
|
||||||
|
{
|
||||||
|
command->m_customCommandArgs.m_arguments.m_floats[numFloats]=floatVal;
|
||||||
|
command->m_customCommandArgs.m_arguments.m_numFloats++;
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
B3_SHARED_API b3SharedMemoryCommandHandle b3GetDynamicsInfoCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, int linkIndex)
|
B3_SHARED_API b3SharedMemoryCommandHandle b3GetDynamicsInfoCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, int linkIndex)
|
||||||
|
|||||||
@@ -62,12 +62,15 @@ B3_SHARED_API int b3GetStatusType(b3SharedMemoryStatusHandle statusHandle);
|
|||||||
|
|
||||||
///Plugin system, load and unload a plugin, execute a command
|
///Plugin system, load and unload a plugin, execute a command
|
||||||
B3_SHARED_API b3SharedMemoryCommandHandle b3CreateCustomCommand(b3PhysicsClientHandle physClient);
|
B3_SHARED_API b3SharedMemoryCommandHandle b3CreateCustomCommand(b3PhysicsClientHandle physClient);
|
||||||
B3_SHARED_API void b3CustomCommandLoadPlugin(b3SharedMemoryCommandHandle commandHandle, const char* pluginPath, int options);
|
B3_SHARED_API void b3CustomCommandLoadPlugin(b3SharedMemoryCommandHandle commandHandle, const char* pluginPath);
|
||||||
B3_SHARED_API int b3GetStatusPluginUniqueId(b3SharedMemoryStatusHandle statusHandle);
|
B3_SHARED_API int b3GetStatusPluginUniqueId(b3SharedMemoryStatusHandle statusHandle);
|
||||||
B3_SHARED_API int b3GetStatusPluginCommandResult(b3SharedMemoryStatusHandle statusHandle);
|
B3_SHARED_API int b3GetStatusPluginCommandResult(b3SharedMemoryStatusHandle statusHandle);
|
||||||
|
|
||||||
B3_SHARED_API void b3CustomCommandUnloadPlugin(b3SharedMemoryCommandHandle commandHandle, int pluginUniqueId);
|
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 void b3CustomCommandExecutePluginCommand(b3SharedMemoryCommandHandle commandHandle, int pluginUniqueId, const char* textArguments);
|
||||||
|
B3_SHARED_API void b3CustomCommandExecuteAddIntArgument(b3SharedMemoryCommandHandle commandHandle, int intVal);
|
||||||
|
B3_SHARED_API void b3CustomCommandExecuteAddFloatArgument(b3SharedMemoryCommandHandle commandHandle, float floatVal);
|
||||||
|
|
||||||
|
|
||||||
B3_SHARED_API int b3GetStatusBodyIndices(b3SharedMemoryStatusHandle statusHandle, int* bodyIndicesOut, int bodyIndicesCapacity);
|
B3_SHARED_API int b3GetStatusBodyIndices(b3SharedMemoryStatusHandle statusHandle, int* bodyIndicesOut, int bodyIndicesCapacity);
|
||||||
|
|
||||||
|
|||||||
@@ -1,5 +1,6 @@
|
|||||||
#include "PhysicsServerCommandProcessor.h"
|
#include "PhysicsServerCommandProcessor.h"
|
||||||
|
|
||||||
|
|
||||||
#include "../Importers/ImportURDFDemo/BulletUrdfImporter.h"
|
#include "../Importers/ImportURDFDemo/BulletUrdfImporter.h"
|
||||||
#include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h"
|
#include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h"
|
||||||
#include "../Importers/ImportURDFDemo/URDF2Bullet.h"
|
#include "../Importers/ImportURDFDemo/URDF2Bullet.h"
|
||||||
@@ -1541,6 +1542,16 @@ struct PhysicsServerCommandProcessorInternalData
|
|||||||
m_pickedConstraint(0),
|
m_pickedConstraint(0),
|
||||||
m_pickingMultiBodyPoint2Point(0)
|
m_pickingMultiBodyPoint2Point(0)
|
||||||
{
|
{
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
{
|
||||||
|
//test to statically link a plugin
|
||||||
|
//#include "plugins/testPlugin/testplugin.h"
|
||||||
|
//register static plugins:
|
||||||
|
//m_pluginManager.registerStaticLinkedPlugin("path", initPlugin, exitPlugin, executePluginCommand);
|
||||||
|
}
|
||||||
|
|
||||||
m_vrControllerEvents.init();
|
m_vrControllerEvents.init();
|
||||||
|
|
||||||
m_bodyHandles.exitHandles();
|
m_bodyHandles.exitHandles();
|
||||||
@@ -1671,14 +1682,24 @@ PhysicsServerCommandProcessor::~PhysicsServerCommandProcessor()
|
|||||||
delete m_data;
|
delete m_data;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void preTickCallback(btDynamicsWorld *world, btScalar timeStep)
|
||||||
|
{
|
||||||
|
PhysicsServerCommandProcessor* proc = (PhysicsServerCommandProcessor*) world->getWorldUserInfo();
|
||||||
|
bool isPreTick = true;
|
||||||
|
proc->tickPlugins(timeStep, isPreTick);
|
||||||
|
}
|
||||||
|
|
||||||
void logCallback(btDynamicsWorld *world, btScalar timeStep)
|
void logCallback(btDynamicsWorld *world, btScalar timeStep)
|
||||||
{
|
{
|
||||||
//handle the logging and playing sounds
|
//handle the logging and playing sounds
|
||||||
PhysicsServerCommandProcessor* proc = (PhysicsServerCommandProcessor*) world->getWorldUserInfo();
|
PhysicsServerCommandProcessor* proc = (PhysicsServerCommandProcessor*) world->getWorldUserInfo();
|
||||||
proc->processCollisionForces(timeStep);
|
proc->processCollisionForces(timeStep);
|
||||||
|
|
||||||
proc->logObjectStates(timeStep);
|
proc->logObjectStates(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)
|
bool MyContactAddedCallback(btManifoldPoint& cp, const btCollisionObjectWrapper* colObj0Wrap,int partId0,int index0,const btCollisionObjectWrapper* colObj1Wrap,int partId1,int index1)
|
||||||
@@ -1786,6 +1807,12 @@ void PhysicsServerCommandProcessor::processCollisionForces(btScalar timeStep)
|
|||||||
#endif//B3_ENABLE_TINY_AUDIO
|
#endif//B3_ENABLE_TINY_AUDIO
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void PhysicsServerCommandProcessor::tickPlugins(btScalar timeStep, bool isPreTick)
|
||||||
|
{
|
||||||
|
m_data->m_pluginManager.tickPlugins(timeStep, isPreTick);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
void PhysicsServerCommandProcessor::logObjectStates(btScalar timeStep)
|
void PhysicsServerCommandProcessor::logObjectStates(btScalar timeStep)
|
||||||
{
|
{
|
||||||
for (int i=0;i<m_data->m_stateLoggers.size();i++)
|
for (int i=0;i<m_data->m_stateLoggers.size();i++)
|
||||||
@@ -2149,7 +2176,11 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld()
|
|||||||
{
|
{
|
||||||
m_data->m_guiHelper->createPhysicsDebugDrawer(m_data->m_dynamicsWorld);
|
m_data->m_guiHelper->createPhysicsDebugDrawer(m_data->m_dynamicsWorld);
|
||||||
}
|
}
|
||||||
m_data->m_dynamicsWorld->setInternalTickCallback(logCallback,this);
|
bool isPreTick=false;
|
||||||
|
m_data->m_dynamicsWorld->setInternalTickCallback(logCallback,this,isPreTick);
|
||||||
|
isPreTick = true;
|
||||||
|
m_data->m_dynamicsWorld->setInternalTickCallback(preTickCallback,this,isPreTick);
|
||||||
|
|
||||||
|
|
||||||
#ifdef B3_ENABLE_TINY_AUDIO
|
#ifdef B3_ENABLE_TINY_AUDIO
|
||||||
m_data->m_soundEngine.init(16,true);
|
m_data->m_soundEngine.init(16,true);
|
||||||
@@ -2966,27 +2997,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
|||||||
bool hasStatus = false;
|
bool hasStatus = false;
|
||||||
|
|
||||||
{
|
{
|
||||||
///we ignore overflow of integer for now
|
|
||||||
|
|
||||||
{
|
{
|
||||||
|
|
||||||
//until we implement a proper ring buffer, we assume always maximum of 1 outstanding commands
|
|
||||||
|
|
||||||
|
|
||||||
//const SharedMemoryCommand& clientCmd =m_data->m_testBlock1->m_clientCommands[0];
|
|
||||||
#if 1
|
|
||||||
if (m_data->m_commandLogger)
|
if (m_data->m_commandLogger)
|
||||||
{
|
{
|
||||||
m_data->m_commandLogger->logCommand(clientCmd);
|
m_data->m_commandLogger->logCommand(clientCmd);
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
//m_data->m_testBlock1->m_numProcessedClientCommands++;
|
|
||||||
|
|
||||||
//no timestamp yet
|
|
||||||
//int timeStamp = 0;
|
|
||||||
|
|
||||||
//catch uninitialized cases
|
|
||||||
serverStatusOut.m_type = CMD_INVALID_STATUS;
|
serverStatusOut.m_type = CMD_INVALID_STATUS;
|
||||||
serverStatusOut.m_numDataStreamBytes = 0;
|
serverStatusOut.m_numDataStreamBytes = 0;
|
||||||
serverStatusOut.m_dataStream = 0;
|
serverStatusOut.m_dataStream = 0;
|
||||||
@@ -2994,32 +3009,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
|||||||
//consume the command
|
//consume the command
|
||||||
switch (clientCmd.m_type)
|
switch (clientCmd.m_type)
|
||||||
{
|
{
|
||||||
#if 0
|
|
||||||
case CMD_SEND_BULLET_DATA_STREAM:
|
|
||||||
{
|
|
||||||
if (m_data->m_verboseOutput)
|
|
||||||
{
|
|
||||||
b3Printf("Processed CMD_SEND_BULLET_DATA_STREAM length %d",clientCmd.m_dataStreamArguments.m_streamChunkLength);
|
|
||||||
}
|
|
||||||
|
|
||||||
btBulletWorldImporter* worldImporter = new btBulletWorldImporter(m_data->m_dynamicsWorld);
|
|
||||||
m_data->m_worldImporters.push_back(worldImporter);
|
|
||||||
bool completedOk = worldImporter->loadFileFromMemory(m_data->m_testBlock1->m_bulletStreamDataClientToServer,clientCmd.m_dataStreamArguments.m_streamChunkLength);
|
|
||||||
|
|
||||||
if (completedOk)
|
|
||||||
{
|
|
||||||
SharedMemoryStatus& status = m_data->createServerStatus(CMD_BULLET_DATA_STREAM_RECEIVED_COMPLETED,clientCmd.m_sequenceNumber,timeStamp);
|
|
||||||
m_data->m_guiHelper->autogenerateGraphicsObjects(this->m_data->m_dynamicsWorld);
|
|
||||||
m_data->submitServerStatus(status);
|
|
||||||
} else
|
|
||||||
{
|
|
||||||
SharedMemoryStatus& status = m_data->createServerStatus(CMD_BULLET_DATA_STREAM_RECEIVED_FAILED,clientCmd.m_sequenceNumber,timeStamp);
|
|
||||||
m_data->submitServerStatus(status);
|
|
||||||
}
|
|
||||||
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
case CMD_STATE_LOGGING:
|
case CMD_STATE_LOGGING:
|
||||||
{
|
{
|
||||||
BT_PROFILE("CMD_STATE_LOGGING");
|
BT_PROFILE("CMD_STATE_LOGGING");
|
||||||
@@ -7996,7 +7986,8 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
|||||||
}
|
}
|
||||||
if (clientCmd.m_updateFlags & CMD_CUSTOM_COMMAND_EXECUTE_PLUGIN_COMMAND)
|
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);
|
|
||||||
|
int result = m_data->m_pluginManager.executePluginCommand(clientCmd.m_customCommandArgs.m_pluginUniqueId, &clientCmd.m_customCommandArgs.m_arguments);
|
||||||
serverCmd.m_customCommandResultArgs.m_executeCommandResult = result;
|
serverCmd.m_customCommandResultArgs.m_executeCommandResult = result;
|
||||||
serverCmd.m_type = CMD_CUSTOM_COMMAND_COMPLETED;
|
serverCmd.m_type = CMD_CUSTOM_COMMAND_COMPLETED;
|
||||||
|
|
||||||
@@ -8245,6 +8236,8 @@ 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)
|
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_vrControllerEvents.addNewVREvents(vrControllerEvents,numVRControllerEvents);
|
||||||
|
|
||||||
|
|
||||||
for (int i=0;i<m_data->m_stateLoggers.size();i++)
|
for (int i=0;i<m_data->m_stateLoggers.size();i++)
|
||||||
{
|
{
|
||||||
if (m_data->m_stateLoggers[i]->m_loggingType==STATE_LOGGING_VR_CONTROLLERS)
|
if (m_data->m_stateLoggers[i]->m_loggingType==STATE_LOGGING_VR_CONTROLLERS)
|
||||||
|
|||||||
@@ -91,6 +91,7 @@ public:
|
|||||||
virtual void replayLogCommand(char* bufferServerToClient, int bufferSizeInBytes );
|
virtual void replayLogCommand(char* bufferServerToClient, int bufferSizeInBytes );
|
||||||
|
|
||||||
//logging of object states (position etc)
|
//logging of object states (position etc)
|
||||||
|
void tickPlugins(btScalar timeStep, bool isPreTick);
|
||||||
void logObjectStates(btScalar timeStep);
|
void logObjectStates(btScalar timeStep);
|
||||||
void processCollisionForces(btScalar timeStep);
|
void processCollisionForces(btScalar timeStep);
|
||||||
|
|
||||||
|
|||||||
@@ -119,10 +119,8 @@ enum CustomCommandEnum
|
|||||||
struct b3CustomCommand
|
struct b3CustomCommand
|
||||||
{
|
{
|
||||||
int m_pluginUniqueId;
|
int m_pluginUniqueId;
|
||||||
int m_commandUniqueId;
|
b3PluginArguments m_arguments;
|
||||||
int m_options;
|
|
||||||
char m_pluginPath[MAX_FILENAME_LENGTH];
|
char m_pluginPath[MAX_FILENAME_LENGTH];
|
||||||
char m_pluginArguments[MAX_FILENAME_LENGTH];
|
|
||||||
};
|
};
|
||||||
|
|
||||||
struct b3CustomCommandResultArgs
|
struct b3CustomCommandResultArgs
|
||||||
|
|||||||
@@ -620,6 +620,19 @@ enum eStateLoggingFlags
|
|||||||
STATE_LOG_JOINT_TORQUES = STATE_LOG_JOINT_MOTOR_TORQUES+STATE_LOG_JOINT_USER_TORQUES,
|
STATE_LOG_JOINT_TORQUES = STATE_LOG_JOINT_MOTOR_TORQUES+STATE_LOG_JOINT_USER_TORQUES,
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#define B3_MAX_PLUGIN_ARG_SIZE 128
|
||||||
|
#define B3_MAX_PLUGIN_ARG_TEXT_LEN 1024
|
||||||
|
|
||||||
|
struct b3PluginArguments
|
||||||
|
{
|
||||||
|
char m_text[B3_MAX_PLUGIN_ARG_TEXT_LEN];
|
||||||
|
int m_numInts;
|
||||||
|
int m_ints[B3_MAX_PLUGIN_ARG_SIZE];
|
||||||
|
int m_numFloats;
|
||||||
|
int m_floats[B3_MAX_PLUGIN_ARG_SIZE];
|
||||||
|
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
#endif//SHARED_MEMORY_PUBLIC_H
|
#endif//SHARED_MEMORY_PUBLIC_H
|
||||||
|
|||||||
@@ -2,7 +2,6 @@
|
|||||||
#include "b3PluginManager.h"
|
#include "b3PluginManager.h"
|
||||||
#include "Bullet3Common/b3HashMap.h"
|
#include "Bullet3Common/b3HashMap.h"
|
||||||
#include "Bullet3Common/b3ResizablePool.h"
|
#include "Bullet3Common/b3ResizablePool.h"
|
||||||
#include "plugins/b3PluginAPI.h"
|
|
||||||
#include "SharedMemoryPublic.h"
|
#include "SharedMemoryPublic.h"
|
||||||
#include "PhysicsDirect.h"
|
#include "PhysicsDirect.h"
|
||||||
#include "plugins/b3PluginContext.h"
|
#include "plugins/b3PluginContext.h"
|
||||||
@@ -30,19 +29,43 @@
|
|||||||
struct b3Plugin
|
struct b3Plugin
|
||||||
{
|
{
|
||||||
B3_DYNLIB_HANDLE m_pluginHandle;
|
B3_DYNLIB_HANDLE m_pluginHandle;
|
||||||
|
bool m_ownsPluginHandle;
|
||||||
std::string m_pluginPath;
|
std::string m_pluginPath;
|
||||||
|
int m_pluginUniqueId;
|
||||||
PFN_INIT m_initFunc;
|
PFN_INIT m_initFunc;
|
||||||
PFN_EXIT m_exitFunc;
|
PFN_EXIT m_exitFunc;
|
||||||
PFN_EXECUTE m_executeCommandFunc;
|
PFN_EXECUTE m_executeCommandFunc;
|
||||||
|
|
||||||
|
PFN_TICK m_preTickFunc;
|
||||||
|
PFN_TICK m_postTickFunc;
|
||||||
|
|
||||||
|
void* m_userPointer;
|
||||||
|
|
||||||
|
b3Plugin()
|
||||||
|
:m_pluginHandle(0),
|
||||||
|
m_ownsPluginHandle(false),
|
||||||
|
m_pluginUniqueId(-1),
|
||||||
|
m_initFunc(0),
|
||||||
|
m_exitFunc(0),
|
||||||
|
m_executeCommandFunc(0),
|
||||||
|
m_postTickFunc(0),
|
||||||
|
m_preTickFunc(0),
|
||||||
|
m_userPointer(0)
|
||||||
|
{
|
||||||
|
}
|
||||||
void clear()
|
void clear()
|
||||||
|
{
|
||||||
|
if (m_ownsPluginHandle)
|
||||||
{
|
{
|
||||||
B3_DYNLIB_CLOSE(m_pluginHandle);
|
B3_DYNLIB_CLOSE(m_pluginHandle);
|
||||||
|
}
|
||||||
m_pluginHandle = 0;
|
m_pluginHandle = 0;
|
||||||
m_initFunc = 0;
|
m_initFunc = 0;
|
||||||
m_exitFunc = 0;
|
m_exitFunc = 0;
|
||||||
m_executeCommandFunc = 0;
|
m_executeCommandFunc = 0;
|
||||||
|
m_preTickFunc = 0;
|
||||||
|
m_postTickFunc = 0;
|
||||||
|
m_userPointer = 0;
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
@@ -64,26 +87,33 @@ b3PluginManager::b3PluginManager(class PhysicsCommandProcessorInterface* physSdk
|
|||||||
|
|
||||||
b3PluginManager::~b3PluginManager()
|
b3PluginManager::~b3PluginManager()
|
||||||
{
|
{
|
||||||
|
while (m_data->m_pluginMap.size())
|
||||||
|
{
|
||||||
|
b3PluginHandle* plugin = m_data->m_pluginMap.getAtIndex(0);
|
||||||
|
unloadPlugin(plugin->m_pluginUniqueId);
|
||||||
|
}
|
||||||
delete m_data->m_physicsDirect;
|
delete m_data->m_physicsDirect;
|
||||||
m_data->m_pluginMap.clear();
|
m_data->m_pluginMap.clear();
|
||||||
m_data->m_plugins.exitHandles();
|
m_data->m_plugins.exitHandles();
|
||||||
delete m_data;
|
delete m_data;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
int b3PluginManager::loadPlugin(const char* pluginPath)
|
int b3PluginManager::loadPlugin(const char* pluginPath)
|
||||||
{
|
{
|
||||||
int pluginUniqueId = -1;
|
int pluginUniqueId = -1;
|
||||||
|
|
||||||
b3Plugin* plugin = m_data->m_pluginMap.find(pluginPath);
|
b3Plugin* pluginOrg = m_data->m_pluginMap.find(pluginPath);
|
||||||
if (plugin)
|
if (pluginOrg)
|
||||||
{
|
{
|
||||||
//already loaded
|
//already loaded
|
||||||
|
pluginUniqueId = pluginOrg->m_pluginUniqueId;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
pluginUniqueId = m_data->m_plugins.allocHandle();
|
pluginUniqueId = m_data->m_plugins.allocHandle();
|
||||||
b3PluginHandle* plugin = m_data->m_plugins.getHandle(pluginUniqueId);
|
b3PluginHandle* plugin = m_data->m_plugins.getHandle(pluginUniqueId);
|
||||||
|
plugin->m_pluginUniqueId = pluginUniqueId;
|
||||||
B3_DYNLIB_HANDLE pluginHandle = B3_DYNLIB_OPEN(pluginPath);
|
B3_DYNLIB_HANDLE pluginHandle = B3_DYNLIB_OPEN(pluginPath);
|
||||||
bool ok = false;
|
bool ok = false;
|
||||||
if (pluginHandle)
|
if (pluginHandle)
|
||||||
@@ -92,13 +122,22 @@ int b3PluginManager::loadPlugin(const char* pluginPath)
|
|||||||
plugin->m_initFunc = (PFN_INIT)B3_DYNLIB_IMPORT(pluginHandle, "initPlugin");
|
plugin->m_initFunc = (PFN_INIT)B3_DYNLIB_IMPORT(pluginHandle, "initPlugin");
|
||||||
plugin->m_exitFunc = (PFN_EXIT)B3_DYNLIB_IMPORT(pluginHandle, "exitPlugin");
|
plugin->m_exitFunc = (PFN_EXIT)B3_DYNLIB_IMPORT(pluginHandle, "exitPlugin");
|
||||||
plugin->m_executeCommandFunc = (PFN_EXECUTE)B3_DYNLIB_IMPORT(pluginHandle, "executePluginCommand");
|
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");
|
||||||
|
|
||||||
if (plugin->m_initFunc && plugin->m_exitFunc && plugin->m_executeCommandFunc)
|
if (plugin->m_initFunc && plugin->m_exitFunc && plugin->m_executeCommandFunc)
|
||||||
{
|
{
|
||||||
int version = plugin->m_initFunc();
|
|
||||||
|
b3PluginContext context;
|
||||||
|
context.m_userPointer = plugin->m_userPointer;
|
||||||
|
context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect;
|
||||||
|
int version = plugin->m_initFunc(&context);
|
||||||
|
//keep the user pointer persistent
|
||||||
|
plugin->m_userPointer = context.m_userPointer;
|
||||||
if (version == SHARED_MEMORY_MAGIC_NUMBER)
|
if (version == SHARED_MEMORY_MAGIC_NUMBER)
|
||||||
{
|
{
|
||||||
ok = true;
|
ok = true;
|
||||||
|
plugin->m_ownsPluginHandle = true;
|
||||||
plugin->m_pluginHandle = pluginHandle;
|
plugin->m_pluginHandle = pluginHandle;
|
||||||
plugin->m_pluginPath = pluginPath;
|
plugin->m_pluginPath = pluginPath;
|
||||||
m_data->m_pluginMap.insert(pluginPath, *plugin);
|
m_data->m_pluginMap.insert(pluginPath, *plugin);
|
||||||
@@ -137,14 +176,35 @@ void b3PluginManager::unloadPlugin(int pluginUniqueId)
|
|||||||
b3PluginHandle* plugin = m_data->m_plugins.getHandle(pluginUniqueId);
|
b3PluginHandle* plugin = m_data->m_plugins.getHandle(pluginUniqueId);
|
||||||
if (plugin)
|
if (plugin)
|
||||||
{
|
{
|
||||||
plugin->m_exitFunc();
|
b3PluginContext context;
|
||||||
|
context.m_userPointer = plugin->m_userPointer;
|
||||||
|
context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect;
|
||||||
|
|
||||||
|
plugin->m_exitFunc(&context);
|
||||||
m_data->m_pluginMap.remove(plugin->m_pluginPath.c_str());
|
m_data->m_pluginMap.remove(plugin->m_pluginPath.c_str());
|
||||||
m_data->m_plugins.freeHandle(pluginUniqueId);
|
m_data->m_plugins.freeHandle(pluginUniqueId);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
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);
|
||||||
|
|
||||||
int b3PluginManager::executePluginCommand(int pluginUniqueId, const char* arguments)
|
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;
|
||||||
|
int result = tick(&context);
|
||||||
|
plugin->m_userPointer = context.m_userPointer;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
int b3PluginManager::executePluginCommand(int pluginUniqueId, const b3PluginArguments* arguments)
|
||||||
{
|
{
|
||||||
int result = -1;
|
int result = -1;
|
||||||
|
|
||||||
@@ -152,9 +212,44 @@ int b3PluginManager::executePluginCommand(int pluginUniqueId, const char* argume
|
|||||||
if (plugin)
|
if (plugin)
|
||||||
{
|
{
|
||||||
b3PluginContext context;
|
b3PluginContext context;
|
||||||
context.m_arguments = arguments;
|
context.m_userPointer = plugin->m_userPointer;
|
||||||
context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect;
|
context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect;
|
||||||
result = plugin->m_executeCommandFunc(&context);
|
|
||||||
|
result = plugin->m_executeCommandFunc(&context, arguments);
|
||||||
|
plugin->m_userPointer = context.m_userPointer;
|
||||||
}
|
}
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
int b3PluginManager::registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT initFunc,PFN_EXIT exitFunc, PFN_EXECUTE executeCommandFunc, PFN_TICK preTickFunc, PFN_TICK postTickFunc)
|
||||||
|
{
|
||||||
|
|
||||||
|
b3Plugin orgPlugin;
|
||||||
|
|
||||||
|
|
||||||
|
int pluginUniqueId = m_data->m_plugins.allocHandle();
|
||||||
|
b3PluginHandle* pluginHandle = m_data->m_plugins.getHandle(pluginUniqueId);
|
||||||
|
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_pluginHandle = 0;
|
||||||
|
pluginHandle->m_pluginPath = pluginPath;
|
||||||
|
pluginHandle->m_userPointer = 0;
|
||||||
|
|
||||||
|
m_data->m_pluginMap.insert(pluginPath, *pluginHandle);
|
||||||
|
|
||||||
|
{
|
||||||
|
b3PluginContext context;
|
||||||
|
context.m_userPointer = 0;
|
||||||
|
context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect;
|
||||||
|
int result = pluginHandle->m_initFunc(&context);
|
||||||
|
pluginHandle->m_userPointer = context.m_userPointer;
|
||||||
|
}
|
||||||
|
return pluginUniqueId;
|
||||||
|
}
|
||||||
|
|||||||
@@ -1,6 +1,8 @@
|
|||||||
#ifndef B3_PLUGIN_MANAGER_H
|
#ifndef B3_PLUGIN_MANAGER_H
|
||||||
#define B3_PLUGIN_MANAGER_H
|
#define B3_PLUGIN_MANAGER_H
|
||||||
|
|
||||||
|
#include "plugins/b3PluginAPI.h"
|
||||||
|
|
||||||
class b3PluginManager
|
class b3PluginManager
|
||||||
{
|
{
|
||||||
struct b3PluginManagerInternalData* m_data;
|
struct b3PluginManagerInternalData* m_data;
|
||||||
@@ -12,7 +14,9 @@ class b3PluginManager
|
|||||||
|
|
||||||
int loadPlugin(const char* pluginPath);
|
int loadPlugin(const char* pluginPath);
|
||||||
void unloadPlugin(int pluginUniqueId);
|
void unloadPlugin(int pluginUniqueId);
|
||||||
int executePluginCommand(int pluginUniqueId, const char* arguments);
|
int executePluginCommand(int pluginUniqueId, const struct b3PluginArguments* arguments);
|
||||||
|
void tickPlugins(double timeStep, bool isPreTick);
|
||||||
|
int registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT initFunc,PFN_EXIT exitFunc, PFN_EXECUTE m_executeCommandFunc, PFN_TICK preTickFunc, PFN_TICK postTickFunc);
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -26,10 +26,10 @@
|
|||||||
extern "C" {
|
extern "C" {
|
||||||
#endif
|
#endif
|
||||||
/* Plugin API */
|
/* Plugin API */
|
||||||
typedef B3_API_ENTRY int (B3_API_CALL * PFN_INIT)();
|
typedef B3_API_ENTRY int (B3_API_CALL * PFN_INIT)(struct b3PluginContext* context);
|
||||||
typedef B3_API_ENTRY void (B3_API_CALL * PFN_EXIT)();
|
typedef B3_API_ENTRY void (B3_API_CALL * PFN_EXIT)(struct b3PluginContext* context);
|
||||||
typedef B3_API_ENTRY int (B3_API_CALL * PFN_EXECUTE)(struct b3PluginContext* context);
|
typedef B3_API_ENTRY int (B3_API_CALL * PFN_EXECUTE)(struct b3PluginContext* context, const struct b3PluginArguments* arguments);
|
||||||
|
typedef B3_API_ENTRY int (B3_API_CALL * PFN_TICK)(struct b3PluginContext* context);
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|||||||
@@ -5,9 +5,17 @@
|
|||||||
|
|
||||||
struct b3PluginContext
|
struct b3PluginContext
|
||||||
{
|
{
|
||||||
const char* m_arguments;
|
|
||||||
|
|
||||||
b3PhysicsClientHandle m_physClient;
|
b3PhysicsClientHandle m_physClient;
|
||||||
|
|
||||||
|
//plugin can modify the m_userPointer to store persistent object pointer (class or struct instance etc)
|
||||||
|
void* m_userPointer;
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#endif //B3_PLUGIN_CONTEXT_H
|
#endif //B3_PLUGIN_CONTEXT_H
|
||||||
@@ -16,22 +16,119 @@ p.unloadPlugin(pluginUid)
|
|||||||
#include "../b3PluginContext.h"
|
#include "../b3PluginContext.h"
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
|
|
||||||
B3_SHARED_API int initPlugin()
|
struct MyClass
|
||||||
{
|
{
|
||||||
|
int m_testData;
|
||||||
|
|
||||||
|
MyClass()
|
||||||
|
:m_testData(42)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
virtual ~MyClass()
|
||||||
|
{
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
B3_SHARED_API int initPlugin(struct b3PluginContext* context)
|
||||||
|
{
|
||||||
|
MyClass* obj = new MyClass();
|
||||||
|
context->m_userPointer = obj;
|
||||||
|
|
||||||
printf("hi!\n");
|
printf("hi!\n");
|
||||||
return SHARED_MEMORY_MAGIC_NUMBER;
|
return SHARED_MEMORY_MAGIC_NUMBER;
|
||||||
}
|
}
|
||||||
|
|
||||||
B3_SHARED_API int executePluginCommand(struct b3PluginContext* context)
|
|
||||||
|
B3_SHARED_API int preTickPluginCallback(struct b3PluginContext* context)
|
||||||
{
|
{
|
||||||
printf("arguments:%s\n",context->m_arguments);
|
MyClass* obj = (MyClass* )context->m_userPointer;
|
||||||
|
|
||||||
|
{
|
||||||
|
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)
|
||||||
|
{
|
||||||
|
//this is only for a test, normally you wouldn't print to the console at each simulation substep!
|
||||||
|
printf("got %d VR controller events!\n", vrEvents.m_numControllerEvents);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
{
|
||||||
|
b3KeyboardEventsData keyboardEventsData;
|
||||||
|
b3SharedMemoryCommandHandle commandHandle = b3RequestKeyboardEventsCommandInit(context->m_physClient);
|
||||||
|
b3SubmitClientCommandAndWaitStatus(context->m_physClient, commandHandle);
|
||||||
|
b3GetKeyboardEventsData(context->m_physClient, &keyboardEventsData);
|
||||||
|
if (keyboardEventsData.m_numKeyboardEvents)
|
||||||
|
{
|
||||||
|
//this is only for a test, normally you wouldn't print to the console at each simulation substep!
|
||||||
|
printf("got %d keyboard events\n", keyboardEventsData.m_numKeyboardEvents);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
{
|
||||||
|
b3MouseEventsData mouseEventsData;
|
||||||
|
b3SharedMemoryCommandHandle commandHandle = b3RequestMouseEventsCommandInit(context->m_physClient);
|
||||||
|
b3SubmitClientCommandAndWaitStatus(context->m_physClient, commandHandle);
|
||||||
|
b3GetMouseEventsData(context->m_physClient, &mouseEventsData);
|
||||||
|
if (mouseEventsData.m_numMouseEvents)
|
||||||
|
{
|
||||||
|
//this is only for a test, normally you wouldn't print to the console at each simulation substep!
|
||||||
|
printf("got %d mouse events\n", mouseEventsData.m_numMouseEvents);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
B3_SHARED_API int postTickPluginCallback(struct b3PluginContext* context)
|
||||||
|
{
|
||||||
|
MyClass* obj = (MyClass* )context->m_userPointer;
|
||||||
|
obj->m_testData++;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
B3_SHARED_API int executePluginCommand(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");
|
||||||
|
|
||||||
|
MyClass* obj = (MyClass*) context->m_userPointer;
|
||||||
|
|
||||||
b3SharedMemoryStatusHandle statusHandle;
|
b3SharedMemoryStatusHandle statusHandle;
|
||||||
int statusType = -1;
|
int statusType = -1;
|
||||||
int bodyUniqueId = -1;
|
int bodyUniqueId = -1;
|
||||||
|
|
||||||
b3SharedMemoryCommandHandle command =
|
b3SharedMemoryCommandHandle command =
|
||||||
b3LoadUrdfCommandInit(context->m_physClient, context->m_arguments);
|
b3LoadUrdfCommandInit(context->m_physClient, arguments->m_text);
|
||||||
|
|
||||||
statusHandle = b3SubmitClientCommandAndWaitStatus(context->m_physClient, command);
|
statusHandle = b3SubmitClientCommandAndWaitStatus(context->m_physClient, command);
|
||||||
statusType = b3GetStatusType(statusHandle);
|
statusType = b3GetStatusType(statusHandle);
|
||||||
@@ -43,7 +140,11 @@ B3_SHARED_API int executePluginCommand(struct b3PluginContext* context)
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
B3_SHARED_API void exitPlugin()
|
B3_SHARED_API void exitPlugin(struct b3PluginContext* context)
|
||||||
{
|
{
|
||||||
|
MyClass* obj = (MyClass*) context->m_userPointer;
|
||||||
|
delete obj;
|
||||||
|
context->m_userPointer = 0;
|
||||||
|
|
||||||
printf("bye!\n");
|
printf("bye!\n");
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -8,9 +8,16 @@ extern "C"
|
|||||||
{
|
{
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
B3_SHARED_API int initPlugin();
|
//initPlugin, exitPlugin and executePluginCommand are required, otherwise plugin won't load
|
||||||
B3_SHARED_API void exitPlugin();
|
B3_SHARED_API int initPlugin(struct b3PluginContext* context);
|
||||||
B3_SHARED_API int executePluginCommand(struct b3PluginContext* context);
|
B3_SHARED_API void exitPlugin(struct b3PluginContext* context);
|
||||||
|
B3_SHARED_API int executePluginCommand(struct b3PluginContext* context, const struct b3PluginArguments* arguments);
|
||||||
|
|
||||||
|
//preTickPluginCallback and postTickPluginCallback are optional.
|
||||||
|
B3_SHARED_API int preTickPluginCallback(struct b3PluginContext* context);
|
||||||
|
B3_SHARED_API int postTickPluginCallback(struct b3PluginContext* context);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -6658,15 +6658,15 @@ static PyObject* pybullet_loadPlugin(PyObject* self,
|
|||||||
PyObject* args, PyObject* keywds)
|
PyObject* args, PyObject* keywds)
|
||||||
{
|
{
|
||||||
int physicsClientId = 0;
|
int physicsClientId = 0;
|
||||||
int option = 0;
|
|
||||||
char* pluginPath = 0;
|
char* pluginPath = 0;
|
||||||
b3SharedMemoryCommandHandle command = 0;
|
b3SharedMemoryCommandHandle command = 0;
|
||||||
b3SharedMemoryStatusHandle statusHandle = 0;
|
b3SharedMemoryStatusHandle statusHandle = 0;
|
||||||
int statusType = -1;
|
int statusType = -1;
|
||||||
|
|
||||||
b3PhysicsClientHandle sm = 0;
|
b3PhysicsClientHandle sm = 0;
|
||||||
static char* kwlist[] = { "pluginPath", "option", "physicsClientId", NULL };
|
static char* kwlist[] = { "pluginPath", "physicsClientId", NULL };
|
||||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|ii", kwlist, &pluginPath, &option, &physicsClientId))
|
if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|i", kwlist, &pluginPath, &physicsClientId))
|
||||||
{
|
{
|
||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
@@ -6679,7 +6679,7 @@ static PyObject* pybullet_loadPlugin(PyObject* self,
|
|||||||
}
|
}
|
||||||
|
|
||||||
command = b3CreateCustomCommand(sm);
|
command = b3CreateCustomCommand(sm);
|
||||||
b3CustomCommandLoadPlugin(command, pluginPath, option);
|
b3CustomCommandLoadPlugin(command, pluginPath);
|
||||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
||||||
statusType = b3GetStatusPluginUniqueId(statusHandle);
|
statusType = b3GetStatusPluginUniqueId(statusHandle);
|
||||||
return PyInt_FromLong(statusType);
|
return PyInt_FromLong(statusType);
|
||||||
@@ -6724,15 +6724,16 @@ static PyObject* pybullet_executePluginCommand(PyObject* self,
|
|||||||
{
|
{
|
||||||
int physicsClientId = 0;
|
int physicsClientId = 0;
|
||||||
int pluginUniqueId = -1;
|
int pluginUniqueId = -1;
|
||||||
int commandUniqueId = -1;
|
char* textArgument = 0;
|
||||||
char* arguments = 0;
|
|
||||||
b3SharedMemoryCommandHandle command=0;
|
b3SharedMemoryCommandHandle command=0;
|
||||||
b3SharedMemoryStatusHandle statusHandle=0;
|
b3SharedMemoryStatusHandle statusHandle=0;
|
||||||
int statusType = -1;
|
int statusType = -1;
|
||||||
|
PyObject* intArgs=0;
|
||||||
|
PyObject* floatArgs=0;
|
||||||
|
|
||||||
b3PhysicsClientHandle sm = 0;
|
b3PhysicsClientHandle sm = 0;
|
||||||
static char* kwlist[] = { "pluginUniqueId", "commandUniqueId", "arguments", "physicsClientId", NULL };
|
static char* kwlist[] = { "pluginUniqueId", "textArgument", "intArgs", "floatArgs", "physicsClientId", NULL };
|
||||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|si", kwlist, &pluginUniqueId, &commandUniqueId, &arguments, &physicsClientId))
|
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|sOOi", kwlist, &pluginUniqueId, &textArgument, &intArgs, &floatArgs, &physicsClientId))
|
||||||
{
|
{
|
||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
@@ -6746,7 +6747,29 @@ static PyObject* pybullet_executePluginCommand(PyObject* self,
|
|||||||
|
|
||||||
|
|
||||||
command = b3CreateCustomCommand(sm);
|
command = b3CreateCustomCommand(sm);
|
||||||
b3CustomCommandExecutePluginCommand(command, pluginUniqueId, commandUniqueId, arguments);
|
b3CustomCommandExecutePluginCommand(command, pluginUniqueId, textArgument);
|
||||||
|
|
||||||
|
{
|
||||||
|
PyObject* seqIntArgs = intArgs?PySequence_Fast(intArgs, "expected a sequence"):0;
|
||||||
|
PyObject* seqFloatArgs = floatArgs?PySequence_Fast(floatArgs, "expected a sequence"):0;
|
||||||
|
int numIntArgs = seqIntArgs?PySequence_Size(intArgs):0;
|
||||||
|
int numFloatArgs = seqIntArgs?PySequence_Size(floatArgs):0;
|
||||||
|
int i;
|
||||||
|
for (i=0;i<numIntArgs;i++)
|
||||||
|
{
|
||||||
|
int val = pybullet_internalGetIntFromSequence(seqIntArgs,i);
|
||||||
|
b3CustomCommandExecuteAddIntArgument(command, val);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
for (i=0;i<numFloatArgs;i++)
|
||||||
|
{
|
||||||
|
float val = pybullet_internalGetFloatFromSequence(seqFloatArgs,i);
|
||||||
|
b3CustomCommandExecuteAddFloatArgument(command, val);
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
||||||
statusType = b3GetStatusPluginCommandResult(statusHandle);
|
statusType = b3GetStatusPluginCommandResult(statusHandle);
|
||||||
return PyInt_FromLong(statusType);
|
return PyInt_FromLong(statusType);
|
||||||
|
|||||||
Reference in New Issue
Block a user