diff --git a/AUTHORS.txt b/AUTHORS.txt index 556e6f641..1bff63207 100644 --- a/AUTHORS.txt +++ b/AUTHORS.txt @@ -2,17 +2,21 @@ Bullet Physics is created by Erwin Coumans with contributions from the following AMD Apple +Yunfei Bai Steve Baker Gino van den Bergen +Jeff Bingham Nicola Candussi Erin Catto Lawrence Chai Erwin Coumans -Christer Ericson Disney Animation +Benjamin Ellenberger +Christer Ericson Google Dirk Gregorius Marcus Hennix +Jasmine Hsu MBSim Development Team Takahiro Harada Simon Hobbs @@ -20,6 +24,7 @@ John Hsu Ole Kniemeyer Jay Lee Francisco Leon +lunkhound Vsevolod Klementjev Phil Knight John McCutchan @@ -32,9 +37,9 @@ Russel Smith Sony Jakub Stephien Marten Svanfeldt +Jie Tan Pierre Terdiman Steven Thompson Tamas Umenhoffer -Yunfei Bai If your name is missing, please send an email to erwin.coumans@gmail.com or file an issue at http://github.com/bulletphysics/bullet3 diff --git a/CMakeLists.txt b/CMakeLists.txt index 8e5f009df..f1d17027b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -449,7 +449,11 @@ configure_file ( ${CMAKE_CURRENT_SOURCE_DIR}/BulletConfig.cmake.in ${CMAKE_CURRENT_BINARY_DIR}/BulletConfig.cmake @ONLY ESCAPE_QUOTES ) -install ( FILES ${CMAKE_CURRENT_SOURCE_DIR}/UseBullet.cmake +OPTION(INSTALL_CMAKE_FILES "Install generated CMake files" ON) + +IF (INSTALL_CMAKE_FILES) + install ( FILES ${CMAKE_CURRENT_SOURCE_DIR}/UseBullet.cmake ${CMAKE_CURRENT_BINARY_DIR}/BulletConfig.cmake DESTINATION ${BULLET_CONFIG_CMAKE_PATH} ) +ENDIF (INSTALL_CMAKE_FILES) diff --git a/Extras/BulletRobotics/CMakeLists.txt b/Extras/BulletRobotics/CMakeLists.txt index a8d238197..3c1b66f53 100644 --- a/Extras/BulletRobotics/CMakeLists.txt +++ b/Extras/BulletRobotics/CMakeLists.txt @@ -32,6 +32,9 @@ SET(BulletRobotics_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 diff --git a/examples/ExampleBrowser/CMakeLists.txt b/examples/ExampleBrowser/CMakeLists.txt index e21d33d40..01d0b5c18 100644 --- a/examples/ExampleBrowser/CMakeLists.txt +++ b/examples/ExampleBrowser/CMakeLists.txt @@ -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 diff --git a/examples/ExampleBrowser/premake4.lua b/examples/ExampleBrowser/premake4.lua index 0ae38bc0f..5aa3b15b5 100644 --- a/examples/ExampleBrowser/premake4.lua +++ b/examples/ExampleBrowser/premake4.lua @@ -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", diff --git a/examples/RobotSimulator/CMakeLists.txt b/examples/RobotSimulator/CMakeLists.txt index 7d35a445e..9549709b0 100644 --- a/examples/RobotSimulator/CMakeLists.txt +++ b/examples/RobotSimulator/CMakeLists.txt @@ -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 diff --git a/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp b/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp index 172a8dfb9..f5556bb60 100644 --- a/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp +++ b/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp @@ -988,7 +988,8 @@ bool b3RobotSimulatorClientAPI::getBodyJacobian(int bodyUniqueId, int linkIndex, if (b3GetStatusType(statusHandle) == CMD_CALCULATED_JACOBIAN_COMPLETED) { - b3GetStatusJacobian(statusHandle, linearJacobian, angularJacobian); + int dofCount; + b3GetStatusJacobian(statusHandle, &dofCount, linearJacobian, angularJacobian); return true; } return false; diff --git a/examples/RobotSimulator/premake4.lua b/examples/RobotSimulator/premake4.lua index faa6fb281..368fefd1f 100644 --- a/examples/RobotSimulator/premake4.lua +++ b/examples/RobotSimulator/premake4.lua @@ -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", diff --git a/examples/SharedMemory/CMakeLists.txt b/examples/SharedMemory/CMakeLists.txt index a369eafa9..c479f7db3 100644 --- a/examples/SharedMemory/CMakeLists.txt +++ b/examples/SharedMemory/CMakeLists.txt @@ -1,5 +1,4 @@ - SET(SharedMemory_SRCS IKTrajectoryHelper.cpp IKTrajectoryHelper.h @@ -41,6 +40,7 @@ SET(SharedMemory_SRCS TinyRendererVisualShapeConverter.h SharedMemoryCommands.h SharedMemoryPublic.h + b3PluginManager.cpp ../TinyRenderer/geometry.cpp ../TinyRenderer/model.cpp ../TinyRenderer/tgaimage.cpp diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index 9bc362373..7ec282897 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -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,137 @@ 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) +{ + 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; + + int len = strlen(pluginPath); + if (lenm_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, const char* textArguments) +{ + + 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_arguments.m_numInts = 0; + command->m_customCommandArgs.m_arguments.m_numFloats = 0; + command->m_customCommandArgs.m_arguments.m_text[0] = 0; + + int len = strlen(textArguments); + + if (lenm_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 (numIntsm_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 (numFloatsm_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) { PhysicsClient* cl = (PhysicsClient* ) physClient; @@ -3178,13 +3310,17 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3CalculateJacobianCommandInit(b3Physi } -B3_SHARED_API int b3GetStatusJacobian(b3SharedMemoryStatusHandle statusHandle, double* linearJacobian, double* angularJacobian) +B3_SHARED_API int b3GetStatusJacobian(b3SharedMemoryStatusHandle statusHandle, int* dofCount, double* linearJacobian, double* angularJacobian) { const SharedMemoryStatus* status = (const SharedMemoryStatus*)statusHandle; btAssert(status->m_type == CMD_CALCULATED_JACOBIAN_COMPLETED); if (status->m_type != CMD_CALCULATED_JACOBIAN_COMPLETED) return false; + if (dofCount) + { + *dofCount = status->m_jacobianResultArgs.m_dofCount; + } if (linearJacobian) { for (int i = 0; i < status->m_jacobianResultArgs.m_dofCount*3; i++) diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index af297ea68..3aa31e3d8 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -60,6 +60,18 @@ 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); +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, 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 b3GetStatusBodyIndex(b3SharedMemoryStatusHandle statusHandle); @@ -304,7 +316,10 @@ B3_SHARED_API int b3GetStatusInverseDynamicsJointForces(b3SharedMemoryStatusHand B3_SHARED_API b3SharedMemoryCommandHandle b3CalculateJacobianCommandInit(b3PhysicsClientHandle physClient, int bodyIndex, int linkIndex, const double* localPosition, const double* jointPositionsQ, const double* jointVelocitiesQdot, const double* jointAccelerations); -B3_SHARED_API int b3GetStatusJacobian(b3SharedMemoryStatusHandle statusHandle, double* linearJacobian, double* angularJacobian); +B3_SHARED_API int b3GetStatusJacobian(b3SharedMemoryStatusHandle statusHandle, + int* dofCount, + double* linearJacobian, + double* angularJacobian); ///compute the joint positions to move the end effector to a desired target using inverse kinematics B3_SHARED_API b3SharedMemoryCommandHandle b3CalculateInverseKinematicsCommandInit(b3PhysicsClientHandle physClient, int bodyIndex); diff --git a/examples/SharedMemory/PhysicsClientSharedMemory.cpp b/examples/SharedMemory/PhysicsClientSharedMemory.cpp index e5cf7b58d..1ea576f65 100644 --- a/examples/SharedMemory/PhysicsClientSharedMemory.cpp +++ b/examples/SharedMemory/PhysicsClientSharedMemory.cpp @@ -78,7 +78,7 @@ struct PhysicsClientSharedMemoryInternalData { m_hasLastServerStatus(false), m_sharedMemoryKey(SHARED_MEMORY_KEY), m_verboseOutput(false), - m_timeOutInSeconds(5) + m_timeOutInSeconds(30) {} void processServerStatus(); @@ -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); diff --git a/examples/SharedMemory/PhysicsDirect.cpp b/examples/SharedMemory/PhysicsDirect.cpp index d26ff70da..2de1acabd 100644 --- a/examples/SharedMemory/PhysicsDirect.cpp +++ b/examples/SharedMemory/PhysicsDirect.cpp @@ -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"); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 1a1b13275..47dff31b3 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -1,5 +1,6 @@ #include "PhysicsServerCommandProcessor.h" + #include "../Importers/ImportURDFDemo/BulletUrdfImporter.h" #include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h" #include "../Importers/ImportURDFDemo/URDF2Bullet.h" @@ -37,6 +38,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 @@ -1053,13 +1056,13 @@ struct GenericRobotStateLogger : public InternalStateLogger std::string m_fileName; FILE* m_logFileHandle; std::string m_structTypes; - btMultiBodyDynamicsWorld* m_dynamicsWorld; + const btMultiBodyDynamicsWorld* m_dynamicsWorld; btAlignedObjectArray m_bodyIdList; bool m_filterObjectUniqueId; int m_maxLogDof; int m_logFlags; - GenericRobotStateLogger(int loggingUniqueId, const std::string& fileName, btMultiBodyDynamicsWorld* dynamicsWorld, int maxLogDof, int logFlags) + GenericRobotStateLogger(int loggingUniqueId, const std::string& fileName, const btMultiBodyDynamicsWorld* dynamicsWorld, int maxLogDof, int logFlags) :m_loggingTimeStamp(0), m_logFileHandle(0), m_dynamicsWorld(dynamicsWorld), @@ -1137,7 +1140,7 @@ struct GenericRobotStateLogger : public InternalStateLogger { for (int i=0;igetNumMultibodies();i++) { - btMultiBody* mb = m_dynamicsWorld->getMultiBody(i); + const btMultiBody* mb = m_dynamicsWorld->getMultiBody(i); int objectUniqueId = mb->getUserIndex2(); if (m_filterObjectUniqueId && m_bodyIdList.findLinearSearch2(objectUniqueId) < 0) { @@ -1430,6 +1433,8 @@ struct PhysicsServerCommandProcessorInternalData b3ResizablePool< InternalBodyHandle > m_bodyHandles; b3ResizablePool m_userCollisionShapeHandles; + b3PluginManager m_pluginManager; + bool m_allowRealTimeSimulation; @@ -1484,7 +1489,7 @@ struct PhysicsServerCommandProcessorInternalData btAlignedObjectArray m_sdfRecentLoadedBodies; - + btAlignedObjectArray m_stateLoggers; int m_stateLoggersUniqueId; int m_profileTimingLoggingUid; @@ -1512,8 +1517,8 @@ struct PhysicsServerCommandProcessorInternalData b3HashMap m_profileEvents; - PhysicsServerCommandProcessorInternalData() - : + PhysicsServerCommandProcessorInternalData(PhysicsCommandProcessorInterface* proc) + :m_pluginManager(proc), m_allowRealTimeSimulation(false), m_commandLogger(0), m_logPlayback(0), @@ -1537,6 +1542,16 @@ struct PhysicsServerCommandProcessorInternalData m_pickedConstraint(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_bodyHandles.exitHandles(); @@ -1643,8 +1658,9 @@ void PhysicsServerCommandProcessor::setGuiHelper(struct GUIHelperInterface* guiH PhysicsServerCommandProcessor::PhysicsServerCommandProcessor() + :m_data(0) { - m_data = new PhysicsServerCommandProcessorInternalData(); + m_data = new PhysicsServerCommandProcessorInternalData(this); createEmptyDynamicsWorld(); @@ -1666,13 +1682,23 @@ PhysicsServerCommandProcessor::~PhysicsServerCommandProcessor() 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) { //handle the logging and playing sounds PhysicsServerCommandProcessor* proc = (PhysicsServerCommandProcessor*) world->getWorldUserInfo(); proc->processCollisionForces(timeStep); - proc->logObjectStates(timeStep); + + bool isPreTick = false; + proc->tickPlugins(timeStep, isPreTick); } @@ -1781,6 +1807,12 @@ void PhysicsServerCommandProcessor::processCollisionForces(btScalar timeStep) #endif//B3_ENABLE_TINY_AUDIO } +void PhysicsServerCommandProcessor::tickPlugins(btScalar timeStep, bool isPreTick) +{ + m_data->m_pluginManager.tickPlugins(timeStep, isPreTick); +} + + void PhysicsServerCommandProcessor::logObjectStates(btScalar timeStep) { for (int i=0;im_stateLoggers.size();i++) @@ -2144,7 +2176,11 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld() { 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 m_data->m_soundEngine.init(16,true); @@ -2961,27 +2997,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm 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) { 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_numDataStreamBytes = 0; serverStatusOut.m_dataStream = 0; @@ -2989,32 +3009,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm //consume the command 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: { BT_PROFILE("CMD_STATE_LOGGING"); @@ -6623,30 +6618,37 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm if (tree) { int baseDofs = bodyHandle->m_multiBody->hasFixedBase() ? 0 : 6; - const int num_dofs = bodyHandle->m_multiBody->getNumDofs(); - btInverseDynamics::vecx nu(num_dofs+baseDofs), qdot(num_dofs + baseDofs), q(num_dofs + baseDofs), joint_force(num_dofs + baseDofs); - for (int i = 0; i < num_dofs; i++) + const int numDofs = bodyHandle->m_multiBody->getNumDofs(); + btInverseDynamics::vecx q(numDofs + baseDofs); + btInverseDynamics::vecx qdot(numDofs + baseDofs); + btInverseDynamics::vecx nu(numDofs + baseDofs); + btInverseDynamics::vecx joint_force(numDofs + baseDofs); + for (int i = 0; i < numDofs; i++) { q[i + baseDofs] = clientCmd.m_calculateJacobianArguments.m_jointPositionsQ[i]; qdot[i + baseDofs] = clientCmd.m_calculateJacobianArguments.m_jointVelocitiesQdot[i]; - nu[i+baseDofs] = clientCmd.m_calculateJacobianArguments.m_jointAccelerations[i]; + nu[i + baseDofs] = clientCmd.m_calculateJacobianArguments.m_jointAccelerations[i]; } // Set the gravity to correspond to the world gravity btInverseDynamics::vec3 id_grav(m_data->m_dynamicsWorld->getGravity()); - if (-1 != tree->setGravityInWorldFrame(id_grav) && -1 != tree->calculateInverseDynamics(q, qdot, nu, &joint_force)) { - serverCmd.m_jacobianResultArgs.m_dofCount = num_dofs; + serverCmd.m_jacobianResultArgs.m_dofCount = numDofs + baseDofs; // Set jacobian value tree->calculateJacobians(q); - btInverseDynamics::mat3x jac_t(3, num_dofs); - tree->getBodyJacobianTrans(clientCmd.m_calculateJacobianArguments.m_linkIndex+1, &jac_t); + btInverseDynamics::mat3x jac_t(3, numDofs + baseDofs); + btInverseDynamics::mat3x jac_r(3, numDofs + baseDofs); + // Note that inverse dynamics uses zero-based indexing of bodies, not starting from -1 for the base link. + tree->getBodyJacobianTrans(clientCmd.m_calculateJacobianArguments.m_linkIndex + 1, &jac_t); + tree->getBodyJacobianRot(clientCmd.m_calculateJacobianArguments.m_linkIndex + 1, &jac_r); for (int i = 0; i < 3; ++i) { - for (int j = 0; j < num_dofs; ++j) + for (int j = 0; j < (numDofs + baseDofs); ++j) { - serverCmd.m_jacobianResultArgs.m_linearJacobian[i*num_dofs+j] = jac_t(i,j); + int element = (numDofs + baseDofs) * i + j; + serverCmd.m_jacobianResultArgs.m_linearJacobian[element] = jac_t(i,j); + serverCmd.m_jacobianResultArgs.m_angularJacobian[element] = jac_r(i,j); } } serverCmd.m_type = CMD_CALCULATED_JACOBIAN_COMPLETED; @@ -7370,7 +7372,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm tree->calculateJacobians(q); btInverseDynamics::mat3x jac_t(3, numDofs); btInverseDynamics::mat3x jac_r(3,numDofs); - // Note that inverse dynamics uses zero-based indexing of bodies, not starting from -1 for the base link. + // Note that inverse dynamics uses zero-based indexing of bodies, not starting from -1 for the base link. tree->getBodyJacobianTrans(endEffectorLinkIndex+1, &jac_t); tree->getBodyJacobianRot(endEffectorLinkIndex+1, &jac_r); for (int i = 0; i < 3; ++i) @@ -7968,6 +7970,39 @@ 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_arguments); + serverCmd.m_customCommandResultArgs.m_executeCommandResult = result; + serverCmd.m_type = CMD_CUSTOM_COMMAND_COMPLETED; + + } + + hasStatus = true; + break; + } default: { BT_PROFILE("CMD_UNKNOWN"); @@ -8186,12 +8221,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; @@ -8214,6 +8243,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) { m_data->m_vrControllerEvents.addNewVREvents(vrControllerEvents,numVRControllerEvents); + + for (int i=0;im_stateLoggers.size();i++) { if (m_data->m_stateLoggers[i]->m_loggingType==STATE_LOGGING_VR_CONTROLLERS) diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.h b/examples/SharedMemory/PhysicsServerCommandProcessor.h index 65bb0bb6d..d46203419 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.h +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.h @@ -91,6 +91,7 @@ public: virtual void replayLogCommand(char* bufferServerToClient, int bufferSizeInBytes ); //logging of object states (position etc) + void tickPlugins(btScalar timeStep, bool isPreTick); void logObjectStates(btScalar timeStep); void processCollisionForces(btScalar timeStep); diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index 357314740..49098e0a0 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -109,6 +109,26 @@ 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; + b3PluginArguments m_arguments; + char m_pluginPath[MAX_FILENAME_LENGTH]; +}; + +struct b3CustomCommandResultArgs +{ + int m_pluginUniqueId; + int m_executeCommandResult; + +}; struct BulletDataStreamArgs { @@ -968,6 +988,7 @@ struct SharedMemoryCommand struct b3RequestCollisionInfoArgs m_requestCollisionInfoArgs; struct b3ChangeTextureArgs m_changeTextureArgs; struct b3SearchPathfArgs m_searchPathArgs; + struct b3CustomCommand m_customCommandArgs; }; }; @@ -1039,6 +1060,7 @@ struct SharedMemoryStatus struct b3SendCollisionInfoArgs m_sendCollisionInfoArgs; struct SendMouseEvents m_sendMouseEvents; struct b3LoadTextureResultArgs m_loadTextureResultArguments; + struct b3CustomCommandResultArgs m_customCommandResultArgs; }; }; diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index cfa605bc4..2186f3a78 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -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 }; @@ -616,6 +620,19 @@ enum eStateLoggingFlags 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 diff --git a/examples/SharedMemory/b3PluginManager.cpp b/examples/SharedMemory/b3PluginManager.cpp new file mode 100644 index 000000000..3210e94b2 --- /dev/null +++ b/examples/SharedMemory/b3PluginManager.cpp @@ -0,0 +1,255 @@ + +#include "b3PluginManager.h" +#include "Bullet3Common/b3HashMap.h" +#include "Bullet3Common/b3ResizablePool.h" +#include "SharedMemoryPublic.h" +#include "PhysicsDirect.h" +#include "plugins/b3PluginContext.h" + +#ifdef _WIN32 + #define WIN32_LEAN_AND_MEAN + #define VC_EXTRALEAN + #include + + typedef HMODULE B3_DYNLIB_HANDLE; + + #define B3_DYNLIB_OPEN LoadLibrary + #define B3_DYNLIB_CLOSE FreeLibrary + #define B3_DYNLIB_IMPORT GetProcAddress +#else + #include + + 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; + bool m_ownsPluginHandle; + std::string m_pluginPath; + int m_pluginUniqueId; + PFN_INIT m_initFunc; + PFN_EXIT m_exitFunc; + 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() + { + if (m_ownsPluginHandle) + { + B3_DYNLIB_CLOSE(m_pluginHandle); + } + m_pluginHandle = 0; + m_initFunc = 0; + m_exitFunc = 0; + m_executeCommandFunc = 0; + m_preTickFunc = 0; + m_postTickFunc = 0; + m_userPointer = 0; + } +}; + +typedef b3PoolBodyHandle b3PluginHandle; + +struct b3PluginManagerInternalData +{ + b3ResizablePool m_plugins; + b3HashMap m_pluginMap; + PhysicsDirect* m_physicsDirect; +}; + +b3PluginManager::b3PluginManager(class PhysicsCommandProcessorInterface* physSdk) +{ + m_data = new b3PluginManagerInternalData; + m_data->m_physicsDirect = new PhysicsDirect(physSdk,false); + +} + +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; + m_data->m_pluginMap.clear(); + m_data->m_plugins.exitHandles(); + delete m_data; +} + + +int b3PluginManager::loadPlugin(const char* pluginPath) +{ + int pluginUniqueId = -1; + + b3Plugin* pluginOrg = m_data->m_pluginMap.find(pluginPath); + if (pluginOrg) + { + //already loaded + pluginUniqueId = pluginOrg->m_pluginUniqueId; + } + else + { + pluginUniqueId = m_data->m_plugins.allocHandle(); + b3PluginHandle* plugin = m_data->m_plugins.getHandle(pluginUniqueId); + plugin->m_pluginUniqueId = 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"); + 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) + { + + 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) + { + ok = true; + plugin->m_ownsPluginHandle = 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) + { + 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_plugins.freeHandle(pluginUniqueId); + } +} + +void b3PluginManager::tickPlugins(double timeStep, bool isPreTick) +{ + for (int i=0;im_pluginMap.size();i++) + { + b3PluginHandle* plugin = m_data->m_pluginMap.getAtIndex(i); + + 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; + + b3PluginHandle* plugin = m_data->m_plugins.getHandle(pluginUniqueId); + if (plugin) + { + b3PluginContext context; + context.m_userPointer = plugin->m_userPointer; + context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect; + + result = plugin->m_executeCommandFunc(&context, arguments); + plugin->m_userPointer = context.m_userPointer; + } + 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; +} diff --git a/examples/SharedMemory/b3PluginManager.h b/examples/SharedMemory/b3PluginManager.h new file mode 100644 index 000000000..dd02b9630 --- /dev/null +++ b/examples/SharedMemory/b3PluginManager.h @@ -0,0 +1,23 @@ +#ifndef B3_PLUGIN_MANAGER_H +#define B3_PLUGIN_MANAGER_H + +#include "plugins/b3PluginAPI.h" + +class b3PluginManager +{ + struct b3PluginManagerInternalData* m_data; + + public: + + b3PluginManager(class PhysicsCommandProcessorInterface* physSdk); + virtual ~b3PluginManager(); + + int loadPlugin(const char* pluginPath); + void unloadPlugin(int pluginUniqueId); + 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); + +}; + +#endif //B3_PLUGIN_MANAGER_H diff --git a/examples/SharedMemory/plugins/b3PluginAPI.h b/examples/SharedMemory/plugins/b3PluginAPI.h new file mode 100644 index 000000000..54387668f --- /dev/null +++ b/examples/SharedMemory/plugins/b3PluginAPI.h @@ -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 __cdecl +#define B3_CALLBACK __cdecl +#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)(struct b3PluginContext* context); + 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, const struct b3PluginArguments* arguments); + typedef B3_API_ENTRY int (B3_API_CALL * PFN_TICK)(struct b3PluginContext* context); +#ifdef __cplusplus +} +#endif + +#endif //B3_PLUGIN_API_H diff --git a/examples/SharedMemory/plugins/b3PluginContext.h b/examples/SharedMemory/plugins/b3PluginContext.h new file mode 100644 index 000000000..cb8bd754d --- /dev/null +++ b/examples/SharedMemory/plugins/b3PluginContext.h @@ -0,0 +1,21 @@ +#ifndef B3_PLUGIN_CONTEXT_H +#define B3_PLUGIN_CONTEXT_H + +#include "../PhysicsClientC_API.h" + +struct b3PluginContext +{ + + 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 \ No newline at end of file diff --git a/examples/SharedMemory/plugins/testPlugin/premake4.lua b/examples/SharedMemory/plugins/testPlugin/premake4.lua new file mode 100644 index 000000000..edc27bacf --- /dev/null +++ b/examples/SharedMemory/plugins/testPlugin/premake4.lua @@ -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", + } + + + diff --git a/examples/SharedMemory/plugins/testPlugin/testplugin.cpp b/examples/SharedMemory/plugins/testPlugin/testplugin.cpp new file mode 100644 index 000000000..2ba2b6bf2 --- /dev/null +++ b/examples/SharedMemory/plugins/testPlugin/testplugin.cpp @@ -0,0 +1,150 @@ + +//test plugin, can load a URDF file, example usage on a Windows machine: + +/* +import pybullet as p +p.connect(p.GUI) +pluginUid = p.loadPlugin("E:/develop/bullet3/bin/pybullet_testplugin_vs2010_x64_debug.dll") +commandUid = 0 +argument = "plane.urdf" +p.executePluginCommand(pluginUid,commandUid,argument) +p.unloadPlugin(pluginUid) +*/ + +#include "testplugin.h" +#include "../../SharedMemoryPublic.h" +#include "../b3PluginContext.h" +#include + +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"); + return SHARED_MEMORY_MAGIC_NUMBER; +} + + +B3_SHARED_API int preTickPluginCallback(struct b3PluginContext* context) +{ + 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;im_numInts;i++) + { + printf("%d", arguments->m_ints[i]); + if ((i+1)m_numInts) + { + printf(","); + } + } + printf("]\nfloat args: ["); + for (int i=0;im_numFloats;i++) + { + printf("%f", arguments->m_floats[i]); + if ((i+1)m_numFloats) + { + printf(","); + } + } + printf("]\n"); + + MyClass* obj = (MyClass*) 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 void exitPlugin(struct b3PluginContext* context) +{ + MyClass* obj = (MyClass*) context->m_userPointer; + delete obj; + context->m_userPointer = 0; + + printf("bye!\n"); +} diff --git a/examples/SharedMemory/plugins/testPlugin/testplugin.h b/examples/SharedMemory/plugins/testPlugin/testplugin.h new file mode 100644 index 000000000..bb14345cc --- /dev/null +++ b/examples/SharedMemory/plugins/testPlugin/testplugin.h @@ -0,0 +1,26 @@ +#ifndef TEST_PLUGIN_H +#define TEST_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(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 +}; +#endif + +#endif//#define TEST_PLUGIN_H diff --git a/examples/SharedMemory/premake4.lua b/examples/SharedMemory/premake4.lua index b7d3ab9e7..d729029a8 100644 --- a/examples/SharedMemory/premake4.lua +++ b/examples/SharedMemory/premake4.lua @@ -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" diff --git a/examples/SharedMemory/tcp/premake4.lua b/examples/SharedMemory/tcp/premake4.lua index b1d5a73ab..9c940402e 100644 --- a/examples/SharedMemory/tcp/premake4.lua +++ b/examples/SharedMemory/tcp/premake4.lua @@ -88,6 +88,9 @@ myfiles = "../SharedMemoryPublic.h", "../PhysicsServerCommandProcessor.cpp", "../PhysicsServerCommandProcessor.h", + "../b3PluginManager.cpp", + "../PhysicsDirect.cpp", + "../PhysicsClient.cpp", "../TinyRendererVisualShapeConverter.cpp", "../TinyRendererVisualShapeConverter.h", "../../TinyRenderer/geometry.cpp", diff --git a/examples/SharedMemory/udp/premake4.lua b/examples/SharedMemory/udp/premake4.lua index a316d6b1c..26aeebc0b 100644 --- a/examples/SharedMemory/udp/premake4.lua +++ b/examples/SharedMemory/udp/premake4.lua @@ -79,6 +79,9 @@ myfiles = "../SharedMemoryPublic.h", "../PhysicsServerCommandProcessor.cpp", "../PhysicsServerCommandProcessor.h", + "../b3PluginManager.cpp", + "../PhysicsDirect.cpp", + "../PhysicsClient.cpp", "../TinyRendererVisualShapeConverter.cpp", "../TinyRendererVisualShapeConverter.h", "../../TinyRenderer/geometry.cpp", diff --git a/examples/pybullet/CMakeLists.txt b/examples/pybullet/CMakeLists.txt index c2f9fd49f..7ca72805b 100644 --- a/examples/pybullet/CMakeLists.txt +++ b/examples/pybullet/CMakeLists.txt @@ -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 diff --git a/examples/pybullet/examples/mimicJointConstraint.py b/examples/pybullet/examples/mimicJointConstraint.py index 60a0625d9..968a24354 100644 --- a/examples/pybullet/examples/mimicJointConstraint.py +++ b/examples/pybullet/examples/mimicJointConstraint.py @@ -23,6 +23,7 @@ p.changeConstraint(c,gearRatio=-1, maxForce=10000) p.setRealTimeSimulation(1) while(1): + p.setGravity(0,0,-10) time.sleep(0.01) #p.removeConstraint(c) - \ No newline at end of file + diff --git a/examples/pybullet/examples/quadruped.py b/examples/pybullet/examples/quadruped.py index 19527fa47..7e3ee1262 100644 --- a/examples/pybullet/examples/quadruped.py +++ b/examples/pybullet/examples/quadruped.py @@ -187,6 +187,7 @@ t = 0.0 t_end = t + 15 ref_time = time.time() while (t=0) - { - b3SetContactFilterBodyA(commandHandle, bodyUniqueIdA); - } - if (bodyUniqueIdB>=0) - { - b3SetContactFilterBodyB(commandHandle, bodyUniqueIdB); - } + if (bodyUniqueIdA>=0) + { + b3SetContactFilterBodyA(commandHandle, bodyUniqueIdA); + } + if (bodyUniqueIdB>=0) + { + b3SetContactFilterBodyB(commandHandle, bodyUniqueIdB); + } - if (linkIndexA>=-1) - { - b3SetContactFilterLinkA( commandHandle, linkIndexA); - } - if (linkIndexB >=-1) - { - b3SetContactFilterLinkB( commandHandle, linkIndexB); - } - + if (linkIndexA>=-1) + { + b3SetContactFilterLinkA( commandHandle, linkIndexA); + } + if (linkIndexB >=-1) + { + b3SetContactFilterLinkB( commandHandle, linkIndexB); + } + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); statusType = b3GetStatusType(statusHandle); if (statusType == CMD_CONTACT_POINT_INFORMATION_COMPLETED) @@ -6574,7 +6574,7 @@ static PyObject* pybullet_invertTransform(PyObject* self, PyErr_SetString(SpamError, "Invalid input: expected position [x,y,z] and orientation [x,y,z,w]."); return NULL; } - + /// quaternion <-> euler yaw/pitch/roll convention from URDF/SDF, see Gazebo /// https://github.com/arpg/Gazebo/blob/master/gazebo/math/Quaternion.cc @@ -6653,6 +6653,131 @@ static PyObject* pybullet_getEulerFromQuaternion(PyObject* self, return Py_None; } + +static PyObject* pybullet_loadPlugin(PyObject* self, + PyObject* args, PyObject* keywds) +{ + int physicsClientId = 0; + + char* pluginPath = 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)) + { + return NULL; + } + + sm = getPhysicsClient(physicsClientId); + if (sm == 0) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + command = b3CreateCustomCommand(sm); + b3CustomCommandLoadPlugin(command, pluginPath); + 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; + char* textArgument = 0; + b3SharedMemoryCommandHandle command=0; + b3SharedMemoryStatusHandle statusHandle=0; + int statusType = -1; + PyObject* intArgs=0; + PyObject* floatArgs=0; + + b3PhysicsClientHandle sm = 0; + static char* kwlist[] = { "pluginUniqueId", "textArgument", "intArgs", "floatArgs", "physicsClientId", NULL }; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|sOOi", kwlist, &pluginUniqueId, &textArgument, &intArgs, &floatArgs, &physicsClientId)) + { + return NULL; + } + + sm = getPhysicsClient(physicsClientId); + if (sm == 0) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + + command = b3CreateCustomCommand(sm); + 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;ib3PhysicsClientHandle__* ///key: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ConnectSharedMemory")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ConnectSharedMemory")] public static extern System.IntPtr b3ConnectSharedMemory(int key) ; /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///key: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ConnectSharedMemory2")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ConnectSharedMemory2")] public static extern System.IntPtr b3ConnectSharedMemory2(int key) ; /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ConnectPhysicsDirect")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ConnectPhysicsDirect")] public static extern System.IntPtr b3ConnectPhysicsDirect() ; /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///argc: int ///argv: char** - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateInProcessPhysicsServerAndConnect")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateInProcessPhysicsServerAndConnect")] public static extern System.IntPtr b3CreateInProcessPhysicsServerAndConnect(int argc, ref System.IntPtr argv) ; /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///argc: int ///argv: char** - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateInProcessPhysicsServerAndConnectSharedMemory")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateInProcessPhysicsServerAndConnectSharedMemory")] public static extern System.IntPtr b3CreateInProcessPhysicsServerAndConnectSharedMemory(int argc, ref System.IntPtr argv) ; /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///argc: int ///argv: char** - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateInProcessPhysicsServerAndConnectMainThread")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateInProcessPhysicsServerAndConnectMainThread")] public static extern System.IntPtr b3CreateInProcessPhysicsServerAndConnectMainThread(int argc, ref System.IntPtr argv) ; /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///argc: int ///argv: char** - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateInProcessPhysicsServerAndConnectMainThreadSharedMemory")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateInProcessPhysicsServerAndConnectMainThreadSharedMemory")] public static extern System.IntPtr b3CreateInProcessPhysicsServerAndConnectMainThreadSharedMemory(int argc, ref System.IntPtr argv) ; /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///guiHelperPtr: void* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect")] public static extern System.IntPtr b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect(System.IntPtr guiHelperPtr) ; /// Return Type: void ///clientHandle: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InProcessRenderSceneInternal")] -public static extern void b3InProcessRenderSceneInternal(ref b3PhysicsClientHandle__ clientHandle) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InProcessRenderSceneInternal")] +public static extern void b3InProcessRenderSceneInternal(System.IntPtr clientHandle) ; /// Return Type: void ///clientHandle: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///debugDrawMode: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InProcessDebugDrawInternal")] -public static extern void b3InProcessDebugDrawInternal(ref b3PhysicsClientHandle__ clientHandle, int debugDrawMode) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InProcessDebugDrawInternal")] +public static extern void b3InProcessDebugDrawInternal(System.IntPtr clientHandle, int debugDrawMode) ; /// Return Type: int ///clientHandle: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///x: float ///y: float - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InProcessMouseMoveCallback")] -public static extern int b3InProcessMouseMoveCallback(ref b3PhysicsClientHandle__ clientHandle, float x, float y) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InProcessMouseMoveCallback")] +public static extern int b3InProcessMouseMoveCallback(System.IntPtr clientHandle, float x, float y) ; /// Return Type: int @@ -1220,60 +1201,60 @@ public static extern int b3InProcessMouseMoveCallback(ref b3PhysicsClientHandle ///state: int ///x: float ///y: float - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InProcessMouseButtonCallback")] -public static extern int b3InProcessMouseButtonCallback(ref b3PhysicsClientHandle__ clientHandle, int button, int state, float x, float y) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InProcessMouseButtonCallback")] +public static extern int b3InProcessMouseButtonCallback(System.IntPtr clientHandle, int button, int state, float x, float y) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3DisconnectSharedMemory")] -public static extern void b3DisconnectSharedMemory(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3DisconnectSharedMemory")] +public static extern void b3DisconnectSharedMemory(System.IntPtr physClient) ; /// Return Type: int ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CanSubmitCommand")] -public static extern int b3CanSubmitCommand(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CanSubmitCommand")] +public static extern int b3CanSubmitCommand(System.IntPtr physClient) ; /// Return Type: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SubmitClientCommandAndWaitStatus")] -public static extern System.IntPtr b3SubmitClientCommandAndWaitStatus(ref b3PhysicsClientHandle__ physClient, ref b3SharedMemoryCommandHandle__ commandHandle) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SubmitClientCommandAndWaitStatus")] +public static extern System.IntPtr b3SubmitClientCommandAndWaitStatus(System.IntPtr physClient, System.IntPtr commandHandle) ; /// Return Type: int ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SubmitClientCommand")] -public static extern int b3SubmitClientCommand(ref b3PhysicsClientHandle__ physClient, ref b3SharedMemoryCommandHandle__ commandHandle) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SubmitClientCommand")] +public static extern int b3SubmitClientCommand(System.IntPtr physClient, System.IntPtr commandHandle) ; /// Return Type: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ProcessServerStatus")] -public static extern System.IntPtr b3ProcessServerStatus(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ProcessServerStatus")] +public static extern System.IntPtr b3ProcessServerStatus(System.IntPtr physClient) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusType")] -public static extern int b3GetStatusType(ref b3SharedMemoryStatusHandle__ statusHandle) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusType")] +public static extern int b3GetStatusType(System.IntPtr statusHandle) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* ///bodyIndicesOut: int* ///bodyIndicesCapacity: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusBodyIndices")] -public static extern int b3GetStatusBodyIndices(ref b3SharedMemoryStatusHandle__ statusHandle, ref int bodyIndicesOut, int bodyIndicesCapacity) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusBodyIndices")] +public static extern int b3GetStatusBodyIndices(System.IntPtr statusHandle, ref int bodyIndicesOut, int bodyIndicesCapacity) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusBodyIndex")] -public static extern int b3GetStatusBodyIndex(ref b3SharedMemoryStatusHandle__ statusHandle) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusBodyIndex")] +public static extern int b3GetStatusBodyIndex(System.IntPtr statusHandle) ; /// Return Type: int @@ -1285,15 +1266,15 @@ public static extern int b3GetStatusBodyIndex(ref b3SharedMemoryStatusHandle__ ///actualStateQ: double** ///actualStateQdot: double** ///jointReactionForces: double** - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusActualState")] -public static extern int b3GetStatusActualState(ref b3SharedMemoryStatusHandle__ statusHandle, ref int bodyUniqueId, ref int numDegreeOfFreedomQ, ref int numDegreeOfFreedomU, ref System.IntPtr rootLocalInertialFrame, ref System.IntPtr actualStateQ, ref System.IntPtr actualStateQdot, ref System.IntPtr jointReactionForces) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusActualState")] +public static extern int b3GetStatusActualState(System.IntPtr statusHandle, ref int bodyUniqueId, ref int numDegreeOfFreedomQ, ref int numDegreeOfFreedomU, ref System.IntPtr rootLocalInertialFrame, ref System.IntPtr actualStateQ, ref System.IntPtr actualStateQdot, ref System.IntPtr jointReactionForces) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCollisionInfoCommandInit")] -public static extern System.IntPtr b3RequestCollisionInfoCommandInit(ref b3PhysicsClientHandle__ physClient, int bodyUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCollisionInfoCommandInit")] +public static extern System.IntPtr b3RequestCollisionInfoCommandInit(System.IntPtr physClient, int bodyUniqueId) ; /// Return Type: int @@ -1301,49 +1282,49 @@ public static extern System.IntPtr b3RequestCollisionInfoCommandInit(ref b3Phys ///linkIndex: int ///aabbMin: double* ///aabbMax: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusAABB")] -public static extern int b3GetStatusAABB(ref b3SharedMemoryStatusHandle__ statusHandle, int linkIndex, ref double aabbMin, ref double aabbMax) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusAABB")] +public static extern int b3GetStatusAABB(System.IntPtr statusHandle, int linkIndex, ref double aabbMin, ref double aabbMax) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitSyncBodyInfoCommand")] -public static extern System.IntPtr b3InitSyncBodyInfoCommand(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitSyncBodyInfoCommand")] +public static extern System.IntPtr b3InitSyncBodyInfoCommand(System.IntPtr physClient) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitRemoveBodyCommand")] -public static extern System.IntPtr b3InitRemoveBodyCommand(ref b3PhysicsClientHandle__ physClient, int bodyUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitRemoveBodyCommand")] +public static extern System.IntPtr b3InitRemoveBodyCommand(System.IntPtr physClient, int bodyUniqueId) ; /// Return Type: int ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetNumBodies")] -public static extern int b3GetNumBodies(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetNumBodies")] +public static extern int b3GetNumBodies(System.IntPtr physClient) ; /// Return Type: int ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///serialIndex: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetBodyUniqueId")] -public static extern int b3GetBodyUniqueId(ref b3PhysicsClientHandle__ physClient, int serialIndex) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetBodyUniqueId")] +public static extern int b3GetBodyUniqueId(System.IntPtr physClient, int serialIndex) ; /// Return Type: int ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyUniqueId: int ///info: b3BodyInfo* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetBodyInfo")] -public static extern int b3GetBodyInfo(ref b3PhysicsClientHandle__ physClient, int bodyUniqueId, ref b3BodyInfo info) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetBodyInfo")] +public static extern int b3GetBodyInfo(System.IntPtr physClient, int bodyUniqueId, ref b3BodyInfo info) ; /// Return Type: int ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyIndex: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetNumJoints")] -public static extern int b3GetNumJoints(ref b3PhysicsClientHandle__ physClient, int bodyIndex) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetNumJoints")] +public static extern int b3GetNumJoints(System.IntPtr physClient, int bodyIndex) ; /// Return Type: int @@ -1351,29 +1332,29 @@ public static extern int b3GetNumJoints(ref b3PhysicsClientHandle__ physClient, ///bodyIndex: int ///jointIndex: int ///info: b3JointInfo* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetJointInfo")] -public static extern int b3GetJointInfo(ref b3PhysicsClientHandle__ physClient, int bodyIndex, int jointIndex, ref b3JointInfo info) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetJointInfo")] +public static extern int b3GetJointInfo(System.IntPtr physClient, int bodyIndex, int jointIndex, ref b3JointInfo info) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyUniqueId: int ///linkIndex: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetDynamicsInfoCommandInit")] -public static extern System.IntPtr b3GetDynamicsInfoCommandInit(ref b3PhysicsClientHandle__ physClient, int bodyUniqueId, int linkIndex) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetDynamicsInfoCommandInit")] +public static extern System.IntPtr b3GetDynamicsInfoCommandInit(System.IntPtr physClient, int bodyUniqueId, int linkIndex) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* ///info: b3DynamicsInfo* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetDynamicsInfo")] -public static extern int b3GetDynamicsInfo(ref b3SharedMemoryStatusHandle__ statusHandle, ref b3DynamicsInfo info) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetDynamicsInfo")] +public static extern int b3GetDynamicsInfo(System.IntPtr statusHandle, ref b3DynamicsInfo info) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitChangeDynamicsInfo")] -public static extern System.IntPtr b3InitChangeDynamicsInfo(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitChangeDynamicsInfo")] +public static extern System.IntPtr b3InitChangeDynamicsInfo(System.IntPtr physClient) ; /// Return Type: int @@ -1381,8 +1362,8 @@ public static extern System.IntPtr b3InitChangeDynamicsInfo(ref b3PhysicsClient ///bodyUniqueId: int ///linkIndex: int ///mass: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ChangeDynamicsInfoSetMass")] -public static extern int b3ChangeDynamicsInfoSetMass(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueId, int linkIndex, double mass) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ChangeDynamicsInfoSetMass")] +public static extern int b3ChangeDynamicsInfoSetMass(System.IntPtr commandHandle, int bodyUniqueId, int linkIndex, double mass) ; /// Return Type: int @@ -1390,8 +1371,8 @@ public static extern int b3ChangeDynamicsInfoSetMass(ref b3SharedMemoryCommandH ///bodyUniqueId: int ///linkIndex: int ///lateralFriction: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ChangeDynamicsInfoSetLateralFriction")] -public static extern int b3ChangeDynamicsInfoSetLateralFriction(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueId, int linkIndex, double lateralFriction) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ChangeDynamicsInfoSetLateralFriction")] +public static extern int b3ChangeDynamicsInfoSetLateralFriction(System.IntPtr commandHandle, int bodyUniqueId, int linkIndex, double lateralFriction) ; /// Return Type: int @@ -1399,8 +1380,8 @@ public static extern int b3ChangeDynamicsInfoSetLateralFriction(ref b3SharedMem ///bodyUniqueId: int ///linkIndex: int ///friction: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ChangeDynamicsInfoSetSpinningFriction")] -public static extern int b3ChangeDynamicsInfoSetSpinningFriction(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueId, int linkIndex, double friction) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ChangeDynamicsInfoSetSpinningFriction")] +public static extern int b3ChangeDynamicsInfoSetSpinningFriction(System.IntPtr commandHandle, int bodyUniqueId, int linkIndex, double friction) ; /// Return Type: int @@ -1408,8 +1389,8 @@ public static extern int b3ChangeDynamicsInfoSetSpinningFriction(ref b3SharedMe ///bodyUniqueId: int ///linkIndex: int ///friction: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ChangeDynamicsInfoSetRollingFriction")] -public static extern int b3ChangeDynamicsInfoSetRollingFriction(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueId, int linkIndex, double friction) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ChangeDynamicsInfoSetRollingFriction")] +public static extern int b3ChangeDynamicsInfoSetRollingFriction(System.IntPtr commandHandle, int bodyUniqueId, int linkIndex, double friction) ; /// Return Type: int @@ -1417,24 +1398,24 @@ public static extern int b3ChangeDynamicsInfoSetRollingFriction(ref b3SharedMem ///bodyUniqueId: int ///linkIndex: int ///restitution: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ChangeDynamicsInfoSetRestitution")] -public static extern int b3ChangeDynamicsInfoSetRestitution(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueId, int linkIndex, double restitution) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ChangeDynamicsInfoSetRestitution")] +public static extern int b3ChangeDynamicsInfoSetRestitution(System.IntPtr commandHandle, int bodyUniqueId, int linkIndex, double restitution) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///bodyUniqueId: int ///linearDamping: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ChangeDynamicsInfoSetLinearDamping")] -public static extern int b3ChangeDynamicsInfoSetLinearDamping(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueId, double linearDamping) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ChangeDynamicsInfoSetLinearDamping")] +public static extern int b3ChangeDynamicsInfoSetLinearDamping(System.IntPtr commandHandle, int bodyUniqueId, double linearDamping) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///bodyUniqueId: int ///angularDamping: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ChangeDynamicsInfoSetAngularDamping")] -public static extern int b3ChangeDynamicsInfoSetAngularDamping(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueId, double angularDamping) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ChangeDynamicsInfoSetAngularDamping")] +public static extern int b3ChangeDynamicsInfoSetAngularDamping(System.IntPtr commandHandle, int bodyUniqueId, double angularDamping) ; /// Return Type: int @@ -1443,8 +1424,8 @@ public static extern int b3ChangeDynamicsInfoSetAngularDamping(ref b3SharedMemo ///linkIndex: int ///contactStiffness: double ///contactDamping: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ChangeDynamicsInfoSetContactStiffnessAndDamping")] -public static extern int b3ChangeDynamicsInfoSetContactStiffnessAndDamping(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueId, int linkIndex, double contactStiffness, double contactDamping) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ChangeDynamicsInfoSetContactStiffnessAndDamping")] +public static extern int b3ChangeDynamicsInfoSetContactStiffnessAndDamping(System.IntPtr commandHandle, int bodyUniqueId, int linkIndex, double contactStiffness, double contactDamping) ; /// Return Type: int @@ -1452,8 +1433,8 @@ public static extern int b3ChangeDynamicsInfoSetContactStiffnessAndDamping(ref ///bodyUniqueId: int ///linkIndex: int ///frictionAnchor: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ChangeDynamicsInfoSetFrictionAnchor")] -public static extern int b3ChangeDynamicsInfoSetFrictionAnchor(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueId, int linkIndex, int frictionAnchor) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ChangeDynamicsInfoSetFrictionAnchor")] +public static extern int b3ChangeDynamicsInfoSetFrictionAnchor(System.IntPtr commandHandle, int bodyUniqueId, int linkIndex, int frictionAnchor) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* @@ -1463,112 +1444,112 @@ public static extern int b3ChangeDynamicsInfoSetFrictionAnchor(ref b3SharedMemo ///childBodyIndex: int ///childJointIndex: int ///info: b3JointInfo* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitCreateUserConstraintCommand")] -public static extern System.IntPtr b3InitCreateUserConstraintCommand(ref b3PhysicsClientHandle__ physClient, int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, ref b3JointInfo info) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitCreateUserConstraintCommand")] +public static extern System.IntPtr b3InitCreateUserConstraintCommand(System.IntPtr physClient, int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, ref b3JointInfo info) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusUserConstraintUniqueId")] -public static extern int b3GetStatusUserConstraintUniqueId(ref b3SharedMemoryStatusHandle__ statusHandle) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusUserConstraintUniqueId")] +public static extern int b3GetStatusUserConstraintUniqueId(System.IntPtr statusHandle) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///userConstraintUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitChangeUserConstraintCommand")] -public static extern System.IntPtr b3InitChangeUserConstraintCommand(ref b3PhysicsClientHandle__ physClient, int userConstraintUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitChangeUserConstraintCommand")] +public static extern System.IntPtr b3InitChangeUserConstraintCommand(System.IntPtr physClient, int userConstraintUniqueId) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///jointChildPivot: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitChangeUserConstraintSetPivotInB")] -public static extern int b3InitChangeUserConstraintSetPivotInB(ref b3SharedMemoryCommandHandle__ commandHandle, ref double jointChildPivot) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitChangeUserConstraintSetPivotInB")] +public static extern int b3InitChangeUserConstraintSetPivotInB(System.IntPtr commandHandle, ref double jointChildPivot) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///jointChildFrameOrn: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitChangeUserConstraintSetFrameInB")] -public static extern int b3InitChangeUserConstraintSetFrameInB(ref b3SharedMemoryCommandHandle__ commandHandle, ref double jointChildFrameOrn) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitChangeUserConstraintSetFrameInB")] +public static extern int b3InitChangeUserConstraintSetFrameInB(System.IntPtr commandHandle, ref double jointChildFrameOrn) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///maxAppliedForce: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitChangeUserConstraintSetMaxForce")] -public static extern int b3InitChangeUserConstraintSetMaxForce(ref b3SharedMemoryCommandHandle__ commandHandle, double maxAppliedForce) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitChangeUserConstraintSetMaxForce")] +public static extern int b3InitChangeUserConstraintSetMaxForce(System.IntPtr commandHandle, double maxAppliedForce) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///gearRatio: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitChangeUserConstraintSetGearRatio")] -public static extern int b3InitChangeUserConstraintSetGearRatio(ref b3SharedMemoryCommandHandle__ commandHandle, double gearRatio) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitChangeUserConstraintSetGearRatio")] +public static extern int b3InitChangeUserConstraintSetGearRatio(System.IntPtr commandHandle, double gearRatio) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///gearAuxLink: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitChangeUserConstraintSetGearAuxLink")] -public static extern int b3InitChangeUserConstraintSetGearAuxLink(ref b3SharedMemoryCommandHandle__ commandHandle, int gearAuxLink) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitChangeUserConstraintSetGearAuxLink")] +public static extern int b3InitChangeUserConstraintSetGearAuxLink(System.IntPtr commandHandle, int gearAuxLink) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///userConstraintUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitRemoveUserConstraintCommand")] -public static extern System.IntPtr b3InitRemoveUserConstraintCommand(ref b3PhysicsClientHandle__ physClient, int userConstraintUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitRemoveUserConstraintCommand")] +public static extern System.IntPtr b3InitRemoveUserConstraintCommand(System.IntPtr physClient, int userConstraintUniqueId) ; /// Return Type: int ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetNumUserConstraints")] -public static extern int b3GetNumUserConstraints(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetNumUserConstraints")] +public static extern int b3GetNumUserConstraints(System.IntPtr physClient) ; /// Return Type: int ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///constraintUniqueId: int ///info: b3UserConstraint* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetUserConstraintInfo")] -public static extern int b3GetUserConstraintInfo(ref b3PhysicsClientHandle__ physClient, int constraintUniqueId, ref b3UserConstraint info) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetUserConstraintInfo")] +public static extern int b3GetUserConstraintInfo(System.IntPtr physClient, int constraintUniqueId, ref b3UserConstraint info) ; /// Return Type: int ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///serialIndex: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetUserConstraintId")] -public static extern int b3GetUserConstraintId(ref b3PhysicsClientHandle__ physClient, int serialIndex) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetUserConstraintId")] +public static extern int b3GetUserConstraintId(System.IntPtr physClient, int serialIndex) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///debugMode: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitRequestDebugLinesCommand")] -public static extern System.IntPtr b3InitRequestDebugLinesCommand(ref b3PhysicsClientHandle__ physClient, int debugMode) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitRequestDebugLinesCommand")] +public static extern System.IntPtr b3InitRequestDebugLinesCommand(System.IntPtr physClient, int debugMode) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///lines: b3DebugLines* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetDebugLines")] -public static extern void b3GetDebugLines(ref b3PhysicsClientHandle__ physClient, ref b3DebugLines lines) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetDebugLines")] +public static extern void b3GetDebugLines(System.IntPtr physClient, ref b3DebugLines lines) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitConfigureOpenGLVisualizer")] -public static extern System.IntPtr b3InitConfigureOpenGLVisualizer(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitConfigureOpenGLVisualizer")] +public static extern System.IntPtr b3InitConfigureOpenGLVisualizer(System.IntPtr physClient) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///flag: int ///enabled: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ConfigureOpenGLVisualizerSetVisualizationFlags")] -public static extern void b3ConfigureOpenGLVisualizerSetVisualizationFlags(ref b3SharedMemoryCommandHandle__ commandHandle, int flag, int enabled) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ConfigureOpenGLVisualizerSetVisualizationFlags")] +public static extern void b3ConfigureOpenGLVisualizerSetVisualizationFlags(System.IntPtr commandHandle, int flag, int enabled) ; /// Return Type: void @@ -1577,21 +1558,21 @@ public static extern void b3ConfigureOpenGLVisualizerSetVisualizationFlags(ref ///cameraPitch: float ///cameraYaw: float ///cameraTargetPosition: float* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ConfigureOpenGLVisualizerSetViewMatrix")] -public static extern void b3ConfigureOpenGLVisualizerSetViewMatrix(ref b3SharedMemoryCommandHandle__ commandHandle, float cameraDistance, float cameraPitch, float cameraYaw, ref float cameraTargetPosition) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ConfigureOpenGLVisualizerSetViewMatrix")] +public static extern void b3ConfigureOpenGLVisualizerSetViewMatrix(System.IntPtr commandHandle, float cameraDistance, float cameraPitch, float cameraYaw, ref float cameraTargetPosition) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitRequestOpenGLVisualizerCameraCommand")] -public static extern System.IntPtr b3InitRequestOpenGLVisualizerCameraCommand(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitRequestOpenGLVisualizerCameraCommand")] +public static extern System.IntPtr b3InitRequestOpenGLVisualizerCameraCommand(System.IntPtr physClient) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* ///camera: b3OpenGLVisualizerCameraInfo* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusOpenGLVisualizerCamera")] -public static extern int b3GetStatusOpenGLVisualizerCamera(ref b3SharedMemoryStatusHandle__ statusHandle, ref b3OpenGLVisualizerCameraInfo camera) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusOpenGLVisualizerCamera")] +public static extern int b3GetStatusOpenGLVisualizerCamera(System.IntPtr statusHandle, ref b3OpenGLVisualizerCameraInfo camera) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* @@ -1601,8 +1582,8 @@ public static extern int b3GetStatusOpenGLVisualizerCamera(ref b3SharedMemorySt ///colorRGB: double* ///lineWidth: double ///lifeTime: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitUserDebugDrawAddLine3D")] -public static extern System.IntPtr b3InitUserDebugDrawAddLine3D(ref b3PhysicsClientHandle__ physClient, ref double fromXYZ, ref double toXYZ, ref double colorRGB, double lineWidth, double lifeTime) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitUserDebugDrawAddLine3D")] +public static extern System.IntPtr b3InitUserDebugDrawAddLine3D(System.IntPtr physClient, ref double fromXYZ, ref double toXYZ, ref double colorRGB, double lineWidth, double lifeTime) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* @@ -1612,30 +1593,30 @@ public static extern System.IntPtr b3InitUserDebugDrawAddLine3D(ref b3PhysicsCl ///colorRGB: double* ///textSize: double ///lifeTime: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitUserDebugDrawAddText3D")] -public static extern System.IntPtr b3InitUserDebugDrawAddText3D(ref b3PhysicsClientHandle__ physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string txt, ref double positionXYZ, ref double colorRGB, double textSize, double lifeTime) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitUserDebugDrawAddText3D")] +public static extern System.IntPtr b3InitUserDebugDrawAddText3D(System.IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string txt, ref double positionXYZ, ref double colorRGB, double textSize, double lifeTime) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///optionFlags: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3UserDebugTextSetOptionFlags")] -public static extern void b3UserDebugTextSetOptionFlags(ref b3SharedMemoryCommandHandle__ commandHandle, int optionFlags) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3UserDebugTextSetOptionFlags")] +public static extern void b3UserDebugTextSetOptionFlags(System.IntPtr commandHandle, int optionFlags) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///orientation: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3UserDebugTextSetOrientation")] -public static extern void b3UserDebugTextSetOrientation(ref b3SharedMemoryCommandHandle__ commandHandle, ref double orientation) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3UserDebugTextSetOrientation")] +public static extern void b3UserDebugTextSetOrientation(System.IntPtr commandHandle, ref double orientation) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///objectUniqueId: int ///linkIndex: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3UserDebugItemSetParentObject")] -public static extern void b3UserDebugItemSetParentObject(ref b3SharedMemoryCommandHandle__ commandHandle, int objectUniqueId, int linkIndex) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3UserDebugItemSetParentObject")] +public static extern void b3UserDebugItemSetParentObject(System.IntPtr commandHandle, int objectUniqueId, int linkIndex) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* @@ -1644,41 +1625,41 @@ public static extern void b3UserDebugItemSetParentObject(ref b3SharedMemoryComm ///rangeMin: double ///rangeMax: double ///startValue: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitUserDebugAddParameter")] -public static extern System.IntPtr b3InitUserDebugAddParameter(ref b3PhysicsClientHandle__ physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string txt, double rangeMin, double rangeMax, double startValue) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitUserDebugAddParameter")] +public static extern System.IntPtr b3InitUserDebugAddParameter(System.IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string txt, double rangeMin, double rangeMax, double startValue) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///debugItemUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitUserDebugReadParameter")] -public static extern System.IntPtr b3InitUserDebugReadParameter(ref b3PhysicsClientHandle__ physClient, int debugItemUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitUserDebugReadParameter")] +public static extern System.IntPtr b3InitUserDebugReadParameter(System.IntPtr physClient, int debugItemUniqueId) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* ///paramValue: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusDebugParameterValue")] -public static extern int b3GetStatusDebugParameterValue(ref b3SharedMemoryStatusHandle__ statusHandle, ref double paramValue) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusDebugParameterValue")] +public static extern int b3GetStatusDebugParameterValue(System.IntPtr statusHandle, ref double paramValue) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///debugItemUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitUserDebugDrawRemove")] -public static extern System.IntPtr b3InitUserDebugDrawRemove(ref b3PhysicsClientHandle__ physClient, int debugItemUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitUserDebugDrawRemove")] +public static extern System.IntPtr b3InitUserDebugDrawRemove(System.IntPtr physClient, int debugItemUniqueId) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitUserDebugDrawRemoveAll")] -public static extern System.IntPtr b3InitUserDebugDrawRemoveAll(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitUserDebugDrawRemoveAll")] +public static extern System.IntPtr b3InitUserDebugDrawRemoveAll(System.IntPtr physClient) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitDebugDrawingCommand")] -public static extern System.IntPtr b3InitDebugDrawingCommand(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitDebugDrawingCommand")] +public static extern System.IntPtr b3InitDebugDrawingCommand(System.IntPtr physClient) ; /// Return Type: void @@ -1686,107 +1667,107 @@ public static extern System.IntPtr b3InitDebugDrawingCommand(ref b3PhysicsClien ///objectUniqueId: int ///linkIndex: int ///objectColorRGB: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetDebugObjectColor")] -public static extern void b3SetDebugObjectColor(ref b3SharedMemoryCommandHandle__ commandHandle, int objectUniqueId, int linkIndex, ref double objectColorRGB) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetDebugObjectColor")] +public static extern void b3SetDebugObjectColor(System.IntPtr commandHandle, int objectUniqueId, int linkIndex, ref double objectColorRGB) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///objectUniqueId: int ///linkIndex: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RemoveDebugObjectColor")] -public static extern void b3RemoveDebugObjectColor(ref b3SharedMemoryCommandHandle__ commandHandle, int objectUniqueId, int linkIndex) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RemoveDebugObjectColor")] +public static extern void b3RemoveDebugObjectColor(System.IntPtr commandHandle, int objectUniqueId, int linkIndex) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetDebugItemUniqueId")] -public static extern int b3GetDebugItemUniqueId(ref b3SharedMemoryStatusHandle__ statusHandle) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetDebugItemUniqueId")] +public static extern int b3GetDebugItemUniqueId(System.IntPtr statusHandle) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitRequestCameraImage")] -public static extern System.IntPtr b3InitRequestCameraImage(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitRequestCameraImage")] +public static extern System.IntPtr b3InitRequestCameraImage(System.IntPtr physClient) ; /// Return Type: void ///command: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///viewMatrix: float* ///projectionMatrix: float* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetCameraMatrices")] -public static extern void b3RequestCameraImageSetCameraMatrices(ref b3SharedMemoryCommandHandle__ command, ref float viewMatrix, ref float projectionMatrix) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetCameraMatrices")] +public static extern void b3RequestCameraImageSetCameraMatrices(System.IntPtr command, ref float viewMatrix, ref float projectionMatrix) ; /// Return Type: void ///command: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///width: int ///height: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetPixelResolution")] -public static extern void b3RequestCameraImageSetPixelResolution(ref b3SharedMemoryCommandHandle__ command, int width, int height) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetPixelResolution")] +public static extern void b3RequestCameraImageSetPixelResolution(System.IntPtr command, int width, int height) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///lightDirection: float* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetLightDirection")] -public static extern void b3RequestCameraImageSetLightDirection(ref b3SharedMemoryCommandHandle__ commandHandle, ref float lightDirection) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetLightDirection")] +public static extern void b3RequestCameraImageSetLightDirection(System.IntPtr commandHandle, ref float lightDirection) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///lightColor: float* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetLightColor")] -public static extern void b3RequestCameraImageSetLightColor(ref b3SharedMemoryCommandHandle__ commandHandle, ref float lightColor) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetLightColor")] +public static extern void b3RequestCameraImageSetLightColor(System.IntPtr commandHandle, ref float lightColor) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///lightDistance: float - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetLightDistance")] -public static extern void b3RequestCameraImageSetLightDistance(ref b3SharedMemoryCommandHandle__ commandHandle, float lightDistance) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetLightDistance")] +public static extern void b3RequestCameraImageSetLightDistance(System.IntPtr commandHandle, float lightDistance) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///lightAmbientCoeff: float - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetLightAmbientCoeff")] -public static extern void b3RequestCameraImageSetLightAmbientCoeff(ref b3SharedMemoryCommandHandle__ commandHandle, float lightAmbientCoeff) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetLightAmbientCoeff")] +public static extern void b3RequestCameraImageSetLightAmbientCoeff(System.IntPtr commandHandle, float lightAmbientCoeff) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///lightDiffuseCoeff: float - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetLightDiffuseCoeff")] -public static extern void b3RequestCameraImageSetLightDiffuseCoeff(ref b3SharedMemoryCommandHandle__ commandHandle, float lightDiffuseCoeff) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetLightDiffuseCoeff")] +public static extern void b3RequestCameraImageSetLightDiffuseCoeff(System.IntPtr commandHandle, float lightDiffuseCoeff) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///lightSpecularCoeff: float - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetLightSpecularCoeff")] -public static extern void b3RequestCameraImageSetLightSpecularCoeff(ref b3SharedMemoryCommandHandle__ commandHandle, float lightSpecularCoeff) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetLightSpecularCoeff")] +public static extern void b3RequestCameraImageSetLightSpecularCoeff(System.IntPtr commandHandle, float lightSpecularCoeff) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///hasShadow: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetShadow")] -public static extern void b3RequestCameraImageSetShadow(ref b3SharedMemoryCommandHandle__ commandHandle, int hasShadow) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetShadow")] +public static extern void b3RequestCameraImageSetShadow(System.IntPtr commandHandle, int hasShadow) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///renderer: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSelectRenderer")] -public static extern void b3RequestCameraImageSelectRenderer(ref b3SharedMemoryCommandHandle__ commandHandle, int renderer) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSelectRenderer")] +public static extern void b3RequestCameraImageSelectRenderer(System.IntPtr commandHandle, int renderer) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///imageData: b3CameraImageData* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetCameraImageData")] -public static extern void b3GetCameraImageData(ref b3PhysicsClientHandle__ physClient, ref b3CameraImageData imageData) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetCameraImageData")] +public static extern void b3GetCameraImageData(System.IntPtr physClient, ref b3CameraImageData imageData) ; /// Return Type: void @@ -1794,7 +1775,7 @@ public static extern void b3GetCameraImageData(ref b3PhysicsClientHandle__ phys ///cameraTargetPosition: float* ///cameraUp: float* ///viewMatrix: float* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ComputeViewMatrixFromPositions")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ComputeViewMatrixFromPositions")] public static extern void b3ComputeViewMatrixFromPositions(ref float cameraPosition, ref float cameraTargetPosition, ref float cameraUp, ref float viewMatrix) ; @@ -1806,7 +1787,7 @@ public static extern void b3ComputeViewMatrixFromPositions(ref float cameraPosi ///roll: float ///upAxis: int ///viewMatrix: float* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ComputeViewMatrixFromYawPitchRoll")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ComputeViewMatrixFromYawPitchRoll")] public static extern void b3ComputeViewMatrixFromYawPitchRoll(ref float cameraTargetPosition, float distance, float yaw, float pitch, float roll, int upAxis, ref float viewMatrix) ; @@ -1815,7 +1796,7 @@ public static extern void b3ComputeViewMatrixFromYawPitchRoll(ref float cameraT ///cameraPosition: float* ///cameraTargetPosition: float* ///cameraUp: float* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ComputePositionFromViewMatrix")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ComputePositionFromViewMatrix")] public static extern void b3ComputePositionFromViewMatrix(ref float viewMatrix, ref float cameraPosition, ref float cameraTargetPosition, ref float cameraUp) ; @@ -1827,7 +1808,7 @@ public static extern void b3ComputePositionFromViewMatrix(ref float viewMatrix, ///nearVal: float ///farVal: float ///projectionMatrix: float* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ComputeProjectionMatrix")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ComputeProjectionMatrix")] public static extern void b3ComputeProjectionMatrix(float left, float right, float bottom, float top, float nearVal, float farVal, ref float projectionMatrix) ; @@ -1837,7 +1818,7 @@ public static extern void b3ComputeProjectionMatrix(float left, float right, fl ///nearVal: float ///farVal: float ///projectionMatrix: float* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ComputeProjectionMatrixFOV")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ComputeProjectionMatrixFOV")] public static extern void b3ComputeProjectionMatrixFOV(float fov, float aspect, float nearVal, float farVal, ref float projectionMatrix) ; @@ -1846,8 +1827,8 @@ public static extern void b3ComputeProjectionMatrixFOV(float fov, float aspect, ///cameraPosition: float* ///cameraTargetPosition: float* ///cameraUp: float* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetViewMatrix")] -public static extern void b3RequestCameraImageSetViewMatrix(ref b3SharedMemoryCommandHandle__ command, ref float cameraPosition, ref float cameraTargetPosition, ref float cameraUp) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetViewMatrix")] +public static extern void b3RequestCameraImageSetViewMatrix(System.IntPtr command, ref float cameraPosition, ref float cameraTargetPosition, ref float cameraUp) ; /// Return Type: void @@ -1858,8 +1839,8 @@ public static extern void b3RequestCameraImageSetViewMatrix(ref b3SharedMemoryC ///pitch: float ///roll: float ///upAxis: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetViewMatrix2")] -public static extern void b3RequestCameraImageSetViewMatrix2(ref b3SharedMemoryCommandHandle__ commandHandle, ref float cameraTargetPosition, float distance, float yaw, float pitch, float roll, int upAxis) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetViewMatrix2")] +public static extern void b3RequestCameraImageSetViewMatrix2(System.IntPtr commandHandle, ref float cameraTargetPosition, float distance, float yaw, float pitch, float roll, int upAxis) ; /// Return Type: void @@ -1870,8 +1851,8 @@ public static extern void b3RequestCameraImageSetViewMatrix2(ref b3SharedMemory ///top: float ///nearVal: float ///farVal: float - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetProjectionMatrix")] -public static extern void b3RequestCameraImageSetProjectionMatrix(ref b3SharedMemoryCommandHandle__ command, float left, float right, float bottom, float top, float nearVal, float farVal) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetProjectionMatrix")] +public static extern void b3RequestCameraImageSetProjectionMatrix(System.IntPtr command, float left, float right, float bottom, float top, float nearVal, float farVal) ; /// Return Type: void @@ -1880,139 +1861,139 @@ public static extern void b3RequestCameraImageSetProjectionMatrix(ref b3SharedM ///aspect: float ///nearVal: float ///farVal: float - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetFOVProjectionMatrix")] -public static extern void b3RequestCameraImageSetFOVProjectionMatrix(ref b3SharedMemoryCommandHandle__ command, float fov, float aspect, float nearVal, float farVal) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetFOVProjectionMatrix")] +public static extern void b3RequestCameraImageSetFOVProjectionMatrix(System.IntPtr command, float fov, float aspect, float nearVal, float farVal) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitRequestContactPointInformation")] -public static extern System.IntPtr b3InitRequestContactPointInformation(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitRequestContactPointInformation")] +public static extern System.IntPtr b3InitRequestContactPointInformation(System.IntPtr physClient) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///bodyUniqueIdA: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetContactFilterBodyA")] -public static extern void b3SetContactFilterBodyA(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueIdA) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetContactFilterBodyA")] +public static extern void b3SetContactFilterBodyA(System.IntPtr commandHandle, int bodyUniqueIdA) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///bodyUniqueIdB: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetContactFilterBodyB")] -public static extern void b3SetContactFilterBodyB(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueIdB) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetContactFilterBodyB")] +public static extern void b3SetContactFilterBodyB(System.IntPtr commandHandle, int bodyUniqueIdB) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///linkIndexA: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetContactFilterLinkA")] -public static extern void b3SetContactFilterLinkA(ref b3SharedMemoryCommandHandle__ commandHandle, int linkIndexA) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetContactFilterLinkA")] +public static extern void b3SetContactFilterLinkA(System.IntPtr commandHandle, int linkIndexA) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///linkIndexB: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetContactFilterLinkB")] -public static extern void b3SetContactFilterLinkB(ref b3SharedMemoryCommandHandle__ commandHandle, int linkIndexB) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetContactFilterLinkB")] +public static extern void b3SetContactFilterLinkB(System.IntPtr commandHandle, int linkIndexB) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///contactPointInfo: b3ContactInformation* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetContactPointInformation")] -public static extern void b3GetContactPointInformation(ref b3PhysicsClientHandle__ physClient, ref b3ContactInformation contactPointInfo) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetContactPointInformation")] +public static extern void b3GetContactPointInformation(System.IntPtr physClient, ref b3ContactInformation contactPointInfo) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitClosestDistanceQuery")] -public static extern System.IntPtr b3InitClosestDistanceQuery(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitClosestDistanceQuery")] +public static extern System.IntPtr b3InitClosestDistanceQuery(System.IntPtr physClient) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///bodyUniqueIdA: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetClosestDistanceFilterBodyA")] -public static extern void b3SetClosestDistanceFilterBodyA(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueIdA) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetClosestDistanceFilterBodyA")] +public static extern void b3SetClosestDistanceFilterBodyA(System.IntPtr commandHandle, int bodyUniqueIdA) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///linkIndexA: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetClosestDistanceFilterLinkA")] -public static extern void b3SetClosestDistanceFilterLinkA(ref b3SharedMemoryCommandHandle__ commandHandle, int linkIndexA) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetClosestDistanceFilterLinkA")] +public static extern void b3SetClosestDistanceFilterLinkA(System.IntPtr commandHandle, int linkIndexA) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///bodyUniqueIdB: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetClosestDistanceFilterBodyB")] -public static extern void b3SetClosestDistanceFilterBodyB(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueIdB) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetClosestDistanceFilterBodyB")] +public static extern void b3SetClosestDistanceFilterBodyB(System.IntPtr commandHandle, int bodyUniqueIdB) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///linkIndexB: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetClosestDistanceFilterLinkB")] -public static extern void b3SetClosestDistanceFilterLinkB(ref b3SharedMemoryCommandHandle__ commandHandle, int linkIndexB) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetClosestDistanceFilterLinkB")] +public static extern void b3SetClosestDistanceFilterLinkB(System.IntPtr commandHandle, int linkIndexB) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///distance: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetClosestDistanceThreshold")] -public static extern void b3SetClosestDistanceThreshold(ref b3SharedMemoryCommandHandle__ commandHandle, double distance) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetClosestDistanceThreshold")] +public static extern void b3SetClosestDistanceThreshold(System.IntPtr commandHandle, double distance) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///contactPointInfo: b3ContactInformation* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetClosestPointInformation")] -public static extern void b3GetClosestPointInformation(ref b3PhysicsClientHandle__ physClient, ref b3ContactInformation contactPointInfo) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetClosestPointInformation")] +public static extern void b3GetClosestPointInformation(System.IntPtr physClient, ref b3ContactInformation contactPointInfo) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///aabbMin: double* ///aabbMax: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitAABBOverlapQuery")] -public static extern System.IntPtr b3InitAABBOverlapQuery(ref b3PhysicsClientHandle__ physClient, ref double aabbMin, ref double aabbMax) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitAABBOverlapQuery")] +public static extern System.IntPtr b3InitAABBOverlapQuery(System.IntPtr physClient, ref double aabbMin, ref double aabbMax) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///data: b3AABBOverlapData* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetAABBOverlapResults")] -public static extern void b3GetAABBOverlapResults(ref b3PhysicsClientHandle__ physClient, ref b3AABBOverlapData data) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetAABBOverlapResults")] +public static extern void b3GetAABBOverlapResults(System.IntPtr physClient, ref b3AABBOverlapData data) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyUniqueIdA: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitRequestVisualShapeInformation")] -public static extern System.IntPtr b3InitRequestVisualShapeInformation(ref b3PhysicsClientHandle__ physClient, int bodyUniqueIdA) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitRequestVisualShapeInformation")] +public static extern System.IntPtr b3InitRequestVisualShapeInformation(System.IntPtr physClient, int bodyUniqueIdA) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///visualShapeInfo: b3VisualShapeInformation* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetVisualShapeInformation")] -public static extern void b3GetVisualShapeInformation(ref b3PhysicsClientHandle__ physClient, ref b3VisualShapeInformation visualShapeInfo) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetVisualShapeInformation")] +public static extern void b3GetVisualShapeInformation(System.IntPtr physClient, ref b3VisualShapeInformation visualShapeInfo) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///filename: char* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitLoadTexture")] -public static extern System.IntPtr b3InitLoadTexture(ref b3PhysicsClientHandle__ physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string filename) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitLoadTexture")] +public static extern System.IntPtr b3InitLoadTexture(System.IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string filename) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusTextureUniqueId")] -public static extern int b3GetStatusTextureUniqueId(ref b3SharedMemoryStatusHandle__ statusHandle) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusTextureUniqueId")] +public static extern int b3GetStatusTextureUniqueId(System.IntPtr statusHandle) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* @@ -2021,8 +2002,8 @@ public static extern int b3GetStatusTextureUniqueId(ref b3SharedMemoryStatusHan ///width: int ///height: int ///rgbPixels: char* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateChangeTextureCommandInit")] -public static extern System.IntPtr b3CreateChangeTextureCommandInit(ref b3PhysicsClientHandle__ physClient, int textureUniqueId, int width, int height, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string rgbPixels) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateChangeTextureCommandInit")] +public static extern System.IntPtr b3CreateChangeTextureCommandInit(System.IntPtr physClient, int textureUniqueId, int width, int height, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string rgbPixels) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* @@ -2031,28 +2012,28 @@ public static extern System.IntPtr b3CreateChangeTextureCommandInit(ref b3Physi ///jointIndex: int ///shapeIndex: int ///textureUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitUpdateVisualShape")] -public static extern System.IntPtr b3InitUpdateVisualShape(ref b3PhysicsClientHandle__ physClient, int bodyUniqueId, int jointIndex, int shapeIndex, int textureUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitUpdateVisualShape")] +public static extern System.IntPtr b3InitUpdateVisualShape(System.IntPtr physClient, int bodyUniqueId, int jointIndex, int shapeIndex, int textureUniqueId) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///rgbaColor: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3UpdateVisualShapeRGBAColor")] -public static extern void b3UpdateVisualShapeRGBAColor(ref b3SharedMemoryCommandHandle__ commandHandle, ref double rgbaColor) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3UpdateVisualShapeRGBAColor")] +public static extern void b3UpdateVisualShapeRGBAColor(System.IntPtr commandHandle, ref double rgbaColor) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///specularColor: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3UpdateVisualShapeSpecularColor")] -public static extern void b3UpdateVisualShapeSpecularColor(ref b3SharedMemoryCommandHandle__ commandHandle, ref double specularColor) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3UpdateVisualShapeSpecularColor")] +public static extern void b3UpdateVisualShapeSpecularColor(System.IntPtr commandHandle, ref double specularColor) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitPhysicsParamCommand")] -public static extern System.IntPtr b3InitPhysicsParamCommand(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitPhysicsParamCommand")] +public static extern System.IntPtr b3InitPhysicsParamCommand(System.IntPtr physClient) ; /// Return Type: int @@ -2060,132 +2041,132 @@ public static extern System.IntPtr b3InitPhysicsParamCommand(ref b3PhysicsClien ///gravx: double ///gravy: double ///gravz: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetGravity")] -public static extern int b3PhysicsParamSetGravity(ref b3SharedMemoryCommandHandle__ commandHandle, double gravx, double gravy, double gravz) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetGravity")] +public static extern int b3PhysicsParamSetGravity(System.IntPtr commandHandle, double gravx, double gravy, double gravz) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///timeStep: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetTimeStep")] -public static extern int b3PhysicsParamSetTimeStep(ref b3SharedMemoryCommandHandle__ commandHandle, double timeStep) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetTimeStep")] +public static extern int b3PhysicsParamSetTimeStep(System.IntPtr commandHandle, double timeStep) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///defaultContactERP: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetDefaultContactERP")] -public static extern int b3PhysicsParamSetDefaultContactERP(ref b3SharedMemoryCommandHandle__ commandHandle, double defaultContactERP) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetDefaultContactERP")] +public static extern int b3PhysicsParamSetDefaultContactERP(System.IntPtr commandHandle, double defaultContactERP) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///defaultNonContactERP: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetDefaultNonContactERP")] -public static extern int b3PhysicsParamSetDefaultNonContactERP(ref b3SharedMemoryCommandHandle__ commandHandle, double defaultNonContactERP) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetDefaultNonContactERP")] +public static extern int b3PhysicsParamSetDefaultNonContactERP(System.IntPtr commandHandle, double defaultNonContactERP) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///frictionERP: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetDefaultFrictionERP")] -public static extern int b3PhysicsParamSetDefaultFrictionERP(ref b3SharedMemoryCommandHandle__ commandHandle, double frictionERP) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetDefaultFrictionERP")] +public static extern int b3PhysicsParamSetDefaultFrictionERP(System.IntPtr commandHandle, double frictionERP) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///numSubSteps: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetNumSubSteps")] -public static extern int b3PhysicsParamSetNumSubSteps(ref b3SharedMemoryCommandHandle__ commandHandle, int numSubSteps) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetNumSubSteps")] +public static extern int b3PhysicsParamSetNumSubSteps(System.IntPtr commandHandle, int numSubSteps) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///enableRealTimeSimulation: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetRealTimeSimulation")] -public static extern int b3PhysicsParamSetRealTimeSimulation(ref b3SharedMemoryCommandHandle__ commandHandle, int enableRealTimeSimulation) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetRealTimeSimulation")] +public static extern int b3PhysicsParamSetRealTimeSimulation(System.IntPtr commandHandle, int enableRealTimeSimulation) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///numSolverIterations: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetNumSolverIterations")] -public static extern int b3PhysicsParamSetNumSolverIterations(ref b3SharedMemoryCommandHandle__ commandHandle, int numSolverIterations) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetNumSolverIterations")] +public static extern int b3PhysicsParamSetNumSolverIterations(System.IntPtr commandHandle, int numSolverIterations) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///filterMode: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetCollisionFilterMode")] -public static extern int b3PhysicsParamSetCollisionFilterMode(ref b3SharedMemoryCommandHandle__ commandHandle, int filterMode) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetCollisionFilterMode")] +public static extern int b3PhysicsParamSetCollisionFilterMode(System.IntPtr commandHandle, int filterMode) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///useSplitImpulse: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetUseSplitImpulse")] -public static extern int b3PhysicsParamSetUseSplitImpulse(ref b3SharedMemoryCommandHandle__ commandHandle, int useSplitImpulse) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetUseSplitImpulse")] +public static extern int b3PhysicsParamSetUseSplitImpulse(System.IntPtr commandHandle, int useSplitImpulse) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///splitImpulsePenetrationThreshold: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetSplitImpulsePenetrationThreshold")] -public static extern int b3PhysicsParamSetSplitImpulsePenetrationThreshold(ref b3SharedMemoryCommandHandle__ commandHandle, double splitImpulsePenetrationThreshold) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetSplitImpulsePenetrationThreshold")] +public static extern int b3PhysicsParamSetSplitImpulsePenetrationThreshold(System.IntPtr commandHandle, double splitImpulsePenetrationThreshold) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///contactBreakingThreshold: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetContactBreakingThreshold")] -public static extern int b3PhysicsParamSetContactBreakingThreshold(ref b3SharedMemoryCommandHandle__ commandHandle, double contactBreakingThreshold) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetContactBreakingThreshold")] +public static extern int b3PhysicsParamSetContactBreakingThreshold(System.IntPtr commandHandle, double contactBreakingThreshold) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///maxNumCmdPer1ms: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetMaxNumCommandsPer1ms")] -public static extern int b3PhysicsParamSetMaxNumCommandsPer1ms(ref b3SharedMemoryCommandHandle__ commandHandle, int maxNumCmdPer1ms) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetMaxNumCommandsPer1ms")] +public static extern int b3PhysicsParamSetMaxNumCommandsPer1ms(System.IntPtr commandHandle, int maxNumCmdPer1ms) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///enableFileCaching: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetEnableFileCaching")] -public static extern int b3PhysicsParamSetEnableFileCaching(ref b3SharedMemoryCommandHandle__ commandHandle, int enableFileCaching) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetEnableFileCaching")] +public static extern int b3PhysicsParamSetEnableFileCaching(System.IntPtr commandHandle, int enableFileCaching) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///restitutionVelocityThreshold: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetRestitutionVelocityThreshold")] -public static extern int b3PhysicsParamSetRestitutionVelocityThreshold(ref b3SharedMemoryCommandHandle__ commandHandle, double restitutionVelocityThreshold) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetRestitutionVelocityThreshold")] +public static extern int b3PhysicsParamSetRestitutionVelocityThreshold(System.IntPtr commandHandle, double restitutionVelocityThreshold) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///flags: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetInternalSimFlags")] -public static extern int b3PhysicsParamSetInternalSimFlags(ref b3SharedMemoryCommandHandle__ commandHandle, int flags) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetInternalSimFlags")] +public static extern int b3PhysicsParamSetInternalSimFlags(System.IntPtr commandHandle, int flags) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitStepSimulationCommand")] -public static extern System.IntPtr b3InitStepSimulationCommand(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitStepSimulationCommand")] +public static extern System.IntPtr b3InitStepSimulationCommand(System.IntPtr physClient) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitResetSimulationCommand")] -public static extern System.IntPtr b3InitResetSimulationCommand(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitResetSimulationCommand")] +public static extern System.IntPtr b3InitResetSimulationCommand(System.IntPtr physClient) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///urdfFileName: char* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadUrdfCommandInit")] -public static extern System.IntPtr b3LoadUrdfCommandInit(ref b3PhysicsClientHandle__ physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string urdfFileName) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadUrdfCommandInit")] +public static extern System.IntPtr b3LoadUrdfCommandInit(System.IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string urdfFileName) ; /// Return Type: int @@ -2193,8 +2174,8 @@ public static extern System.IntPtr b3LoadUrdfCommandInit(ref b3PhysicsClientHan ///startPosX: double ///startPosY: double ///startPosZ: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadUrdfCommandSetStartPosition")] -public static extern int b3LoadUrdfCommandSetStartPosition(ref b3SharedMemoryCommandHandle__ commandHandle, double startPosX, double startPosY, double startPosZ) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadUrdfCommandSetStartPosition")] +public static extern int b3LoadUrdfCommandSetStartPosition(System.IntPtr commandHandle, double startPosX, double startPosY, double startPosZ) ; /// Return Type: int @@ -2203,64 +2184,64 @@ public static extern int b3LoadUrdfCommandSetStartPosition(ref b3SharedMemoryCo ///startOrnY: double ///startOrnZ: double ///startOrnW: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadUrdfCommandSetStartOrientation")] -public static extern int b3LoadUrdfCommandSetStartOrientation(ref b3SharedMemoryCommandHandle__ commandHandle, double startOrnX, double startOrnY, double startOrnZ, double startOrnW) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadUrdfCommandSetStartOrientation")] +public static extern int b3LoadUrdfCommandSetStartOrientation(System.IntPtr commandHandle, double startOrnX, double startOrnY, double startOrnZ, double startOrnW) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///useMultiBody: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadUrdfCommandSetUseMultiBody")] -public static extern int b3LoadUrdfCommandSetUseMultiBody(ref b3SharedMemoryCommandHandle__ commandHandle, int useMultiBody) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadUrdfCommandSetUseMultiBody")] +public static extern int b3LoadUrdfCommandSetUseMultiBody(System.IntPtr commandHandle, int useMultiBody) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///useFixedBase: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadUrdfCommandSetUseFixedBase")] -public static extern int b3LoadUrdfCommandSetUseFixedBase(ref b3SharedMemoryCommandHandle__ commandHandle, int useFixedBase) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadUrdfCommandSetUseFixedBase")] +public static extern int b3LoadUrdfCommandSetUseFixedBase(System.IntPtr commandHandle, int useFixedBase) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///flags: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadUrdfCommandSetFlags")] -public static extern int b3LoadUrdfCommandSetFlags(ref b3SharedMemoryCommandHandle__ commandHandle, int flags) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadUrdfCommandSetFlags")] +public static extern int b3LoadUrdfCommandSetFlags(System.IntPtr commandHandle, int flags) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///globalScaling: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadUrdfCommandSetGlobalScaling")] -public static extern int b3LoadUrdfCommandSetGlobalScaling(ref b3SharedMemoryCommandHandle__ commandHandle, double globalScaling) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadUrdfCommandSetGlobalScaling")] +public static extern int b3LoadUrdfCommandSetGlobalScaling(System.IntPtr commandHandle, double globalScaling) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///fileName: char* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadBulletCommandInit")] -public static extern System.IntPtr b3LoadBulletCommandInit(ref b3PhysicsClientHandle__ physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadBulletCommandInit")] +public static extern System.IntPtr b3LoadBulletCommandInit(System.IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///fileName: char* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SaveBulletCommandInit")] -public static extern System.IntPtr b3SaveBulletCommandInit(ref b3PhysicsClientHandle__ physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SaveBulletCommandInit")] +public static extern System.IntPtr b3SaveBulletCommandInit(System.IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///fileName: char* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadMJCFCommandInit")] -public static extern System.IntPtr b3LoadMJCFCommandInit(ref b3PhysicsClientHandle__ physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadMJCFCommandInit")] +public static extern System.IntPtr b3LoadMJCFCommandInit(System.IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///flags: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadMJCFCommandSetFlags")] -public static extern void b3LoadMJCFCommandSetFlags(ref b3SharedMemoryCommandHandle__ commandHandle, int flags) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadMJCFCommandSetFlags")] +public static extern void b3LoadMJCFCommandSetFlags(System.IntPtr commandHandle, int flags) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* @@ -2269,8 +2250,8 @@ public static extern void b3LoadMJCFCommandSetFlags(ref b3SharedMemoryCommandHa ///jointPositionsQ: double* ///jointVelocitiesQdot: double* ///jointAccelerations: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CalculateInverseDynamicsCommandInit")] -public static extern System.IntPtr b3CalculateInverseDynamicsCommandInit(ref b3PhysicsClientHandle__ physClient, int bodyIndex, ref double jointPositionsQ, ref double jointVelocitiesQdot, ref double jointAccelerations) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CalculateInverseDynamicsCommandInit")] +public static extern System.IntPtr b3CalculateInverseDynamicsCommandInit(System.IntPtr physClient, int bodyIndex, ref double jointPositionsQ, ref double jointVelocitiesQdot, ref double jointAccelerations) ; /// Return Type: int @@ -2278,8 +2259,8 @@ public static extern System.IntPtr b3CalculateInverseDynamicsCommandInit(ref b3 ///bodyUniqueId: int* ///dofCount: int* ///jointForces: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusInverseDynamicsJointForces")] -public static extern int b3GetStatusInverseDynamicsJointForces(ref b3SharedMemoryStatusHandle__ statusHandle, ref int bodyUniqueId, ref int dofCount, ref double jointForces) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusInverseDynamicsJointForces")] +public static extern int b3GetStatusInverseDynamicsJointForces(System.IntPtr statusHandle, ref int bodyUniqueId, ref int dofCount, ref double jointForces) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* @@ -2290,31 +2271,31 @@ public static extern int b3GetStatusInverseDynamicsJointForces(ref b3SharedMemo ///jointPositionsQ: double* ///jointVelocitiesQdot: double* ///jointAccelerations: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CalculateJacobianCommandInit")] -public static extern System.IntPtr b3CalculateJacobianCommandInit(ref b3PhysicsClientHandle__ physClient, int bodyIndex, int linkIndex, ref double localPosition, ref double jointPositionsQ, ref double jointVelocitiesQdot, ref double jointAccelerations) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CalculateJacobianCommandInit")] +public static extern System.IntPtr b3CalculateJacobianCommandInit(System.IntPtr physClient, int bodyIndex, int linkIndex, ref double localPosition, ref double jointPositionsQ, ref double jointVelocitiesQdot, ref double jointAccelerations) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* ///linearJacobian: double* ///angularJacobian: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusJacobian")] -public static extern int b3GetStatusJacobian(ref b3SharedMemoryStatusHandle__ statusHandle, ref double linearJacobian, ref double angularJacobian) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusJacobian")] +public static extern int b3GetStatusJacobian(System.IntPtr statusHandle, ref double linearJacobian, ref double angularJacobian) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyIndex: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CalculateInverseKinematicsCommandInit")] -public static extern System.IntPtr b3CalculateInverseKinematicsCommandInit(ref b3PhysicsClientHandle__ physClient, int bodyIndex) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CalculateInverseKinematicsCommandInit")] +public static extern System.IntPtr b3CalculateInverseKinematicsCommandInit(System.IntPtr physClient, int bodyIndex) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///endEffectorLinkIndex: int ///targetPosition: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CalculateInverseKinematicsAddTargetPurePosition")] -public static extern void b3CalculateInverseKinematicsAddTargetPurePosition(ref b3SharedMemoryCommandHandle__ commandHandle, int endEffectorLinkIndex, ref double targetPosition) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CalculateInverseKinematicsAddTargetPurePosition")] +public static extern void b3CalculateInverseKinematicsAddTargetPurePosition(System.IntPtr commandHandle, int endEffectorLinkIndex, ref double targetPosition) ; /// Return Type: void @@ -2322,8 +2303,8 @@ public static extern void b3CalculateInverseKinematicsAddTargetPurePosition(ref ///endEffectorLinkIndex: int ///targetPosition: double* ///targetOrientation: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CalculateInverseKinematicsAddTargetPositionWithOrientation")] -public static extern void b3CalculateInverseKinematicsAddTargetPositionWithOrientation(ref b3SharedMemoryCommandHandle__ commandHandle, int endEffectorLinkIndex, ref double targetPosition, ref double targetOrientation) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CalculateInverseKinematicsAddTargetPositionWithOrientation")] +public static extern void b3CalculateInverseKinematicsAddTargetPositionWithOrientation(System.IntPtr commandHandle, int endEffectorLinkIndex, ref double targetPosition, ref double targetOrientation) ; /// Return Type: void @@ -2335,8 +2316,8 @@ public static extern void b3CalculateInverseKinematicsAddTargetPositionWithOrie ///upperLimit: double* ///jointRange: double* ///restPose: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CalculateInverseKinematicsPosWithNullSpaceVel")] -public static extern void b3CalculateInverseKinematicsPosWithNullSpaceVel(ref b3SharedMemoryCommandHandle__ commandHandle, int numDof, int endEffectorLinkIndex, ref double targetPosition, ref double lowerLimit, ref double upperLimit, ref double jointRange, ref double restPose) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CalculateInverseKinematicsPosWithNullSpaceVel")] +public static extern void b3CalculateInverseKinematicsPosWithNullSpaceVel(System.IntPtr commandHandle, int numDof, int endEffectorLinkIndex, ref double targetPosition, ref double lowerLimit, ref double upperLimit, ref double jointRange, ref double restPose) ; /// Return Type: void @@ -2349,16 +2330,16 @@ public static extern void b3CalculateInverseKinematicsPosWithNullSpaceVel(ref b ///upperLimit: double* ///jointRange: double* ///restPose: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CalculateInverseKinematicsPosOrnWithNullSpaceVel")] -public static extern void b3CalculateInverseKinematicsPosOrnWithNullSpaceVel(ref b3SharedMemoryCommandHandle__ commandHandle, int numDof, int endEffectorLinkIndex, ref double targetPosition, ref double targetOrientation, ref double lowerLimit, ref double upperLimit, ref double jointRange, ref double restPose) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CalculateInverseKinematicsPosOrnWithNullSpaceVel")] +public static extern void b3CalculateInverseKinematicsPosOrnWithNullSpaceVel(System.IntPtr commandHandle, int numDof, int endEffectorLinkIndex, ref double targetPosition, ref double targetOrientation, ref double lowerLimit, ref double upperLimit, ref double jointRange, ref double restPose) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///numDof: int ///jointDampingCoeff: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CalculateInverseKinematicsSetJointDamping")] -public static extern void b3CalculateInverseKinematicsSetJointDamping(ref b3SharedMemoryCommandHandle__ commandHandle, int numDof, ref double jointDampingCoeff) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CalculateInverseKinematicsSetJointDamping")] +public static extern void b3CalculateInverseKinematicsSetJointDamping(System.IntPtr commandHandle, int numDof, ref double jointDampingCoeff) ; /// Return Type: int @@ -2366,159 +2347,159 @@ public static extern void b3CalculateInverseKinematicsSetJointDamping(ref b3Sha ///bodyUniqueId: int* ///dofCount: int* ///jointPositions: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusInverseKinematicsJointPositions")] -public static extern int b3GetStatusInverseKinematicsJointPositions(ref b3SharedMemoryStatusHandle__ statusHandle, ref int bodyUniqueId, ref int dofCount, ref double jointPositions) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusInverseKinematicsJointPositions")] +public static extern int b3GetStatusInverseKinematicsJointPositions(System.IntPtr statusHandle, ref int bodyUniqueId, ref int dofCount, ref double jointPositions) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///sdfFileName: char* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadSdfCommandInit")] -public static extern System.IntPtr b3LoadSdfCommandInit(ref b3PhysicsClientHandle__ physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string sdfFileName) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadSdfCommandInit")] +public static extern System.IntPtr b3LoadSdfCommandInit(System.IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string sdfFileName) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///useMultiBody: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadSdfCommandSetUseMultiBody")] -public static extern int b3LoadSdfCommandSetUseMultiBody(ref b3SharedMemoryCommandHandle__ commandHandle, int useMultiBody) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadSdfCommandSetUseMultiBody")] +public static extern int b3LoadSdfCommandSetUseMultiBody(System.IntPtr commandHandle, int useMultiBody) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///globalScaling: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadSdfCommandSetUseGlobalScaling")] -public static extern int b3LoadSdfCommandSetUseGlobalScaling(ref b3SharedMemoryCommandHandle__ commandHandle, double globalScaling) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadSdfCommandSetUseGlobalScaling")] +public static extern int b3LoadSdfCommandSetUseGlobalScaling(System.IntPtr commandHandle, double globalScaling) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///sdfFileName: char* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SaveWorldCommandInit")] -public static extern System.IntPtr b3SaveWorldCommandInit(ref b3PhysicsClientHandle__ physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string sdfFileName) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SaveWorldCommandInit")] +public static extern System.IntPtr b3SaveWorldCommandInit(System.IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string sdfFileName) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///controlMode: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3JointControlCommandInit")] -public static extern System.IntPtr b3JointControlCommandInit(ref b3PhysicsClientHandle__ physClient, int controlMode) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3JointControlCommandInit")] +public static extern System.IntPtr b3JointControlCommandInit(System.IntPtr physClient, int controlMode) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyUniqueId: int ///controlMode: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3JointControlCommandInit2")] -public static extern System.IntPtr b3JointControlCommandInit2(ref b3PhysicsClientHandle__ physClient, int bodyUniqueId, int controlMode) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3JointControlCommandInit2")] +public static extern System.IntPtr b3JointControlCommandInit2(System.IntPtr physClient, int bodyUniqueId, int controlMode) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///qIndex: int ///value: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3JointControlSetDesiredPosition")] -public static extern int b3JointControlSetDesiredPosition(ref b3SharedMemoryCommandHandle__ commandHandle, int qIndex, double value) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3JointControlSetDesiredPosition")] +public static extern int b3JointControlSetDesiredPosition(System.IntPtr commandHandle, int qIndex, double value) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///dofIndex: int ///value: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3JointControlSetKp")] -public static extern int b3JointControlSetKp(ref b3SharedMemoryCommandHandle__ commandHandle, int dofIndex, double value) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3JointControlSetKp")] +public static extern int b3JointControlSetKp(System.IntPtr commandHandle, int dofIndex, double value) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///dofIndex: int ///value: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3JointControlSetKd")] -public static extern int b3JointControlSetKd(ref b3SharedMemoryCommandHandle__ commandHandle, int dofIndex, double value) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3JointControlSetKd")] +public static extern int b3JointControlSetKd(System.IntPtr commandHandle, int dofIndex, double value) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///dofIndex: int ///value: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3JointControlSetDesiredVelocity")] -public static extern int b3JointControlSetDesiredVelocity(ref b3SharedMemoryCommandHandle__ commandHandle, int dofIndex, double value) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3JointControlSetDesiredVelocity")] +public static extern int b3JointControlSetDesiredVelocity(System.IntPtr commandHandle, int dofIndex, double value) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///dofIndex: int ///value: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3JointControlSetMaximumForce")] -public static extern int b3JointControlSetMaximumForce(ref b3SharedMemoryCommandHandle__ commandHandle, int dofIndex, double value) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3JointControlSetMaximumForce")] +public static extern int b3JointControlSetMaximumForce(System.IntPtr commandHandle, int dofIndex, double value) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///dofIndex: int ///value: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3JointControlSetDesiredForceTorque")] -public static extern int b3JointControlSetDesiredForceTorque(ref b3SharedMemoryCommandHandle__ commandHandle, int dofIndex, double value) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3JointControlSetDesiredForceTorque")] +public static extern int b3JointControlSetDesiredForceTorque(System.IntPtr commandHandle, int dofIndex, double value) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateCollisionShapeCommandInit")] -public static extern System.IntPtr b3CreateCollisionShapeCommandInit(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateCollisionShapeCommandInit")] +public static extern System.IntPtr b3CreateCollisionShapeCommandInit(System.IntPtr physClient) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///radius: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateCollisionShapeAddSphere")] -public static extern int b3CreateCollisionShapeAddSphere(ref b3SharedMemoryCommandHandle__ commandHandle, double radius) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateCollisionShapeAddSphere")] +public static extern int b3CreateCollisionShapeAddSphere(System.IntPtr commandHandle, double radius) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///halfExtents: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateCollisionShapeAddBox")] -public static extern int b3CreateCollisionShapeAddBox(ref b3SharedMemoryCommandHandle__ commandHandle, ref double halfExtents) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateCollisionShapeAddBox")] +public static extern int b3CreateCollisionShapeAddBox(System.IntPtr commandHandle, ref double halfExtents) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///radius: double ///height: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateCollisionShapeAddCapsule")] -public static extern int b3CreateCollisionShapeAddCapsule(ref b3SharedMemoryCommandHandle__ commandHandle, double radius, double height) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateCollisionShapeAddCapsule")] +public static extern int b3CreateCollisionShapeAddCapsule(System.IntPtr commandHandle, double radius, double height) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///radius: double ///height: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateCollisionShapeAddCylinder")] -public static extern int b3CreateCollisionShapeAddCylinder(ref b3SharedMemoryCommandHandle__ commandHandle, double radius, double height) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateCollisionShapeAddCylinder")] +public static extern int b3CreateCollisionShapeAddCylinder(System.IntPtr commandHandle, double radius, double height) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///planeNormal: double* ///planeConstant: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateCollisionShapeAddPlane")] -public static extern int b3CreateCollisionShapeAddPlane(ref b3SharedMemoryCommandHandle__ commandHandle, ref double planeNormal, double planeConstant) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateCollisionShapeAddPlane")] +public static extern int b3CreateCollisionShapeAddPlane(System.IntPtr commandHandle, ref double planeNormal, double planeConstant) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///fileName: char* ///meshScale: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateCollisionShapeAddMesh")] -public static extern int b3CreateCollisionShapeAddMesh(ref b3SharedMemoryCommandHandle__ commandHandle, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName, ref double meshScale) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateCollisionShapeAddMesh")] +public static extern int b3CreateCollisionShapeAddMesh(System.IntPtr commandHandle, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName, ref double meshScale) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///shapeIndex: int ///flags: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateCollisionSetFlag")] -public static extern void b3CreateCollisionSetFlag(ref b3SharedMemoryCommandHandle__ commandHandle, int shapeIndex, int flags) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateCollisionSetFlag")] +public static extern void b3CreateCollisionSetFlag(System.IntPtr commandHandle, int shapeIndex, int flags) ; /// Return Type: void @@ -2526,32 +2507,32 @@ public static extern void b3CreateCollisionSetFlag(ref b3SharedMemoryCommandHan ///shapeIndex: int ///childPosition: double* ///childOrientation: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateCollisionShapeSetChildTransform")] -public static extern void b3CreateCollisionShapeSetChildTransform(ref b3SharedMemoryCommandHandle__ commandHandle, int shapeIndex, ref double childPosition, ref double childOrientation) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateCollisionShapeSetChildTransform")] +public static extern void b3CreateCollisionShapeSetChildTransform(System.IntPtr commandHandle, int shapeIndex, ref double childPosition, ref double childOrientation) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusCollisionShapeUniqueId")] -public static extern int b3GetStatusCollisionShapeUniqueId(ref b3SharedMemoryStatusHandle__ statusHandle) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusCollisionShapeUniqueId")] +public static extern int b3GetStatusCollisionShapeUniqueId(System.IntPtr statusHandle) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateVisualShapeCommandInit")] -public static extern System.IntPtr b3CreateVisualShapeCommandInit(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateVisualShapeCommandInit")] +public static extern System.IntPtr b3CreateVisualShapeCommandInit(System.IntPtr physClient) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusVisualShapeUniqueId")] -public static extern int b3GetStatusVisualShapeUniqueId(ref b3SharedMemoryStatusHandle__ statusHandle) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusVisualShapeUniqueId")] +public static extern int b3GetStatusVisualShapeUniqueId(System.IntPtr statusHandle) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateMultiBodyCommandInit")] -public static extern System.IntPtr b3CreateMultiBodyCommandInit(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateMultiBodyCommandInit")] +public static extern System.IntPtr b3CreateMultiBodyCommandInit(System.IntPtr physClient) ; /// Return Type: int @@ -2563,8 +2544,8 @@ public static extern System.IntPtr b3CreateMultiBodyCommandInit(ref b3PhysicsCl ///baseOrientation: double* ///baseInertialFramePosition: double* ///baseInertialFrameOrientation: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateMultiBodyBase")] -public static extern int b3CreateMultiBodyBase(ref b3SharedMemoryCommandHandle__ commandHandle, double mass, int collisionShapeUnique, int visualShapeUniqueId, ref double basePosition, ref double baseOrientation, ref double baseInertialFramePosition, ref double baseInertialFrameOrientation) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateMultiBodyBase")] +public static extern int b3CreateMultiBodyBase(System.IntPtr commandHandle, double mass, int collisionShapeUnique, int visualShapeUniqueId, ref double basePosition, ref double baseOrientation, ref double baseInertialFramePosition, ref double baseInertialFrameOrientation) ; /// Return Type: int @@ -2579,20 +2560,20 @@ public static extern int b3CreateMultiBodyBase(ref b3SharedMemoryCommandHandle_ ///linkParentIndex: int ///linkJointType: int ///linkJointAxis: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateMultiBodyLink")] -public static extern int b3CreateMultiBodyLink(ref b3SharedMemoryCommandHandle__ commandHandle, double linkMass, double linkCollisionShapeIndex, double linkVisualShapeIndex, ref double linkPosition, ref double linkOrientation, ref double linkInertialFramePosition, ref double linkInertialFrameOrientation, int linkParentIndex, int linkJointType, ref double linkJointAxis) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateMultiBodyLink")] +public static extern int b3CreateMultiBodyLink(System.IntPtr commandHandle, double linkMass, double linkCollisionShapeIndex, double linkVisualShapeIndex, ref double linkPosition, ref double linkOrientation, ref double linkInertialFramePosition, ref double linkInertialFrameOrientation, int linkParentIndex, int linkJointType, ref double linkJointAxis) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateMultiBodyUseMaximalCoordinates")] -public static extern void b3CreateMultiBodyUseMaximalCoordinates(ref b3SharedMemoryCommandHandle__ commandHandle) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateMultiBodyUseMaximalCoordinates")] +public static extern void b3CreateMultiBodyUseMaximalCoordinates(System.IntPtr commandHandle) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateBoxShapeCommandInit")] -public static extern System.IntPtr b3CreateBoxShapeCommandInit(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateBoxShapeCommandInit")] +public static extern System.IntPtr b3CreateBoxShapeCommandInit(System.IntPtr physClient) ; /// Return Type: int @@ -2600,8 +2581,8 @@ public static extern System.IntPtr b3CreateBoxShapeCommandInit(ref b3PhysicsCli ///startPosX: double ///startPosY: double ///startPosZ: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateBoxCommandSetStartPosition")] -public static extern int b3CreateBoxCommandSetStartPosition(ref b3SharedMemoryCommandHandle__ commandHandle, double startPosX, double startPosY, double startPosZ) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateBoxCommandSetStartPosition")] +public static extern int b3CreateBoxCommandSetStartPosition(System.IntPtr commandHandle, double startPosX, double startPosY, double startPosZ) ; /// Return Type: int @@ -2610,8 +2591,8 @@ public static extern int b3CreateBoxCommandSetStartPosition(ref b3SharedMemoryC ///startOrnY: double ///startOrnZ: double ///startOrnW: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateBoxCommandSetStartOrientation")] -public static extern int b3CreateBoxCommandSetStartOrientation(ref b3SharedMemoryCommandHandle__ commandHandle, double startOrnX, double startOrnY, double startOrnZ, double startOrnW) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateBoxCommandSetStartOrientation")] +public static extern int b3CreateBoxCommandSetStartOrientation(System.IntPtr commandHandle, double startOrnX, double startOrnY, double startOrnZ, double startOrnW) ; /// Return Type: int @@ -2619,22 +2600,22 @@ public static extern int b3CreateBoxCommandSetStartOrientation(ref b3SharedMemo ///halfExtentsX: double ///halfExtentsY: double ///halfExtentsZ: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateBoxCommandSetHalfExtents")] -public static extern int b3CreateBoxCommandSetHalfExtents(ref b3SharedMemoryCommandHandle__ commandHandle, double halfExtentsX, double halfExtentsY, double halfExtentsZ) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateBoxCommandSetHalfExtents")] +public static extern int b3CreateBoxCommandSetHalfExtents(System.IntPtr commandHandle, double halfExtentsX, double halfExtentsY, double halfExtentsZ) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///mass: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateBoxCommandSetMass")] -public static extern int b3CreateBoxCommandSetMass(ref b3SharedMemoryCommandHandle__ commandHandle, double mass) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateBoxCommandSetMass")] +public static extern int b3CreateBoxCommandSetMass(System.IntPtr commandHandle, double mass) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///collisionShapeType: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateBoxCommandSetCollisionShapeType")] -public static extern int b3CreateBoxCommandSetCollisionShapeType(ref b3SharedMemoryCommandHandle__ commandHandle, int collisionShapeType) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateBoxCommandSetCollisionShapeType")] +public static extern int b3CreateBoxCommandSetCollisionShapeType(System.IntPtr commandHandle, int collisionShapeType) ; /// Return Type: int @@ -2643,15 +2624,15 @@ public static extern int b3CreateBoxCommandSetCollisionShapeType(ref b3SharedMe ///green: double ///blue: double ///alpha: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateBoxCommandSetColorRGBA")] -public static extern int b3CreateBoxCommandSetColorRGBA(ref b3SharedMemoryCommandHandle__ commandHandle, double red, double green, double blue, double alpha) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateBoxCommandSetColorRGBA")] +public static extern int b3CreateBoxCommandSetColorRGBA(System.IntPtr commandHandle, double red, double green, double blue, double alpha) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyIndex: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreatePoseCommandInit")] -public static extern System.IntPtr b3CreatePoseCommandInit(ref b3PhysicsClientHandle__ physClient, int bodyIndex) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreatePoseCommandInit")] +public static extern System.IntPtr b3CreatePoseCommandInit(System.IntPtr physClient, int bodyIndex) ; /// Return Type: int @@ -2659,8 +2640,8 @@ public static extern System.IntPtr b3CreatePoseCommandInit(ref b3PhysicsClientH ///startPosX: double ///startPosY: double ///startPosZ: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreatePoseCommandSetBasePosition")] -public static extern int b3CreatePoseCommandSetBasePosition(ref b3SharedMemoryCommandHandle__ commandHandle, double startPosX, double startPosY, double startPosZ) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreatePoseCommandSetBasePosition")] +public static extern int b3CreatePoseCommandSetBasePosition(System.IntPtr commandHandle, double startPosX, double startPosY, double startPosZ) ; /// Return Type: int @@ -2669,30 +2650,30 @@ public static extern int b3CreatePoseCommandSetBasePosition(ref b3SharedMemoryC ///startOrnY: double ///startOrnZ: double ///startOrnW: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreatePoseCommandSetBaseOrientation")] -public static extern int b3CreatePoseCommandSetBaseOrientation(ref b3SharedMemoryCommandHandle__ commandHandle, double startOrnX, double startOrnY, double startOrnZ, double startOrnW) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreatePoseCommandSetBaseOrientation")] +public static extern int b3CreatePoseCommandSetBaseOrientation(System.IntPtr commandHandle, double startOrnX, double startOrnY, double startOrnZ, double startOrnW) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///linVel: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreatePoseCommandSetBaseLinearVelocity")] -public static extern int b3CreatePoseCommandSetBaseLinearVelocity(ref b3SharedMemoryCommandHandle__ commandHandle, ref double linVel) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreatePoseCommandSetBaseLinearVelocity")] +public static extern int b3CreatePoseCommandSetBaseLinearVelocity(System.IntPtr commandHandle, ref double linVel) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///angVel: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreatePoseCommandSetBaseAngularVelocity")] -public static extern int b3CreatePoseCommandSetBaseAngularVelocity(ref b3SharedMemoryCommandHandle__ commandHandle, ref double angVel) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreatePoseCommandSetBaseAngularVelocity")] +public static extern int b3CreatePoseCommandSetBaseAngularVelocity(System.IntPtr commandHandle, ref double angVel) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///numJointPositions: int ///jointPositions: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreatePoseCommandSetJointPositions")] -public static extern int b3CreatePoseCommandSetJointPositions(ref b3SharedMemoryCommandHandle__ commandHandle, int numJointPositions, ref double jointPositions) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreatePoseCommandSetJointPositions")] +public static extern int b3CreatePoseCommandSetJointPositions(System.IntPtr commandHandle, int numJointPositions, ref double jointPositions) ; /// Return Type: int @@ -2700,8 +2681,8 @@ public static extern int b3CreatePoseCommandSetJointPositions(ref b3SharedMemor ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///jointIndex: int ///jointPosition: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreatePoseCommandSetJointPosition")] -public static extern int b3CreatePoseCommandSetJointPosition(ref b3PhysicsClientHandle__ physClient, ref b3SharedMemoryCommandHandle__ commandHandle, int jointIndex, double jointPosition) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreatePoseCommandSetJointPosition")] +public static extern int b3CreatePoseCommandSetJointPosition(System.IntPtr physClient, System.IntPtr commandHandle, int jointIndex, double jointPosition) ; /// Return Type: int @@ -2709,8 +2690,8 @@ public static extern int b3CreatePoseCommandSetJointPosition(ref b3PhysicsClien ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///numJointVelocities: int ///jointVelocities: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreatePoseCommandSetJointVelocities")] -public static extern int b3CreatePoseCommandSetJointVelocities(ref b3PhysicsClientHandle__ physClient, ref b3SharedMemoryCommandHandle__ commandHandle, int numJointVelocities, ref double jointVelocities) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreatePoseCommandSetJointVelocities")] +public static extern int b3CreatePoseCommandSetJointVelocities(System.IntPtr physClient, System.IntPtr commandHandle, int numJointVelocities, ref double jointVelocities) ; /// Return Type: int @@ -2718,45 +2699,45 @@ public static extern int b3CreatePoseCommandSetJointVelocities(ref b3PhysicsCli ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///jointIndex: int ///jointVelocity: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreatePoseCommandSetJointVelocity")] -public static extern int b3CreatePoseCommandSetJointVelocity(ref b3PhysicsClientHandle__ physClient, ref b3SharedMemoryCommandHandle__ commandHandle, int jointIndex, double jointVelocity) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreatePoseCommandSetJointVelocity")] +public static extern int b3CreatePoseCommandSetJointVelocity(System.IntPtr physClient, System.IntPtr commandHandle, int jointIndex, double jointVelocity) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateSensorCommandInit")] -public static extern System.IntPtr b3CreateSensorCommandInit(ref b3PhysicsClientHandle__ physClient, int bodyUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateSensorCommandInit")] +public static extern System.IntPtr b3CreateSensorCommandInit(System.IntPtr physClient, int bodyUniqueId) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///jointIndex: int ///enable: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateSensorEnable6DofJointForceTorqueSensor")] -public static extern int b3CreateSensorEnable6DofJointForceTorqueSensor(ref b3SharedMemoryCommandHandle__ commandHandle, int jointIndex, int enable) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateSensorEnable6DofJointForceTorqueSensor")] +public static extern int b3CreateSensorEnable6DofJointForceTorqueSensor(System.IntPtr commandHandle, int jointIndex, int enable) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///linkIndex: int ///enable: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateSensorEnableIMUForLink")] -public static extern int b3CreateSensorEnableIMUForLink(ref b3SharedMemoryCommandHandle__ commandHandle, int linkIndex, int enable) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateSensorEnableIMUForLink")] +public static extern int b3CreateSensorEnableIMUForLink(System.IntPtr commandHandle, int linkIndex, int enable) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestActualStateCommandInit")] -public static extern System.IntPtr b3RequestActualStateCommandInit(ref b3PhysicsClientHandle__ physClient, int bodyUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestActualStateCommandInit")] +public static extern System.IntPtr b3RequestActualStateCommandInit(System.IntPtr physClient, int bodyUniqueId) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///computeLinkVelocity: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestActualStateCommandComputeLinkVelocity")] -public static extern int b3RequestActualStateCommandComputeLinkVelocity(ref b3SharedMemoryCommandHandle__ commandHandle, int computeLinkVelocity) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestActualStateCommandComputeLinkVelocity")] +public static extern int b3RequestActualStateCommandComputeLinkVelocity(System.IntPtr commandHandle, int computeLinkVelocity) ; /// Return Type: int @@ -2764,8 +2745,8 @@ public static extern int b3RequestActualStateCommandComputeLinkVelocity(ref b3S ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* ///jointIndex: int ///state: b3JointSensorState* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetJointState")] -public static extern int b3GetJointState(ref b3PhysicsClientHandle__ physClient, ref b3SharedMemoryStatusHandle__ statusHandle, int jointIndex, ref b3JointSensorState state) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetJointState")] +public static extern int b3GetJointState(System.IntPtr physClient, System.IntPtr statusHandle, int jointIndex, ref b3JointSensorState state) ; /// Return Type: int @@ -2773,8 +2754,8 @@ public static extern int b3GetJointState(ref b3PhysicsClientHandle__ physClient ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* ///linkIndex: int ///state: b3LinkState* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetLinkState")] -public static extern int b3GetLinkState(ref b3PhysicsClientHandle__ physClient, ref b3SharedMemoryStatusHandle__ statusHandle, int linkIndex, ref b3LinkState state) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetLinkState")] +public static extern int b3GetLinkState(System.IntPtr physClient, System.IntPtr statusHandle, int linkIndex, ref b3LinkState state) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* @@ -2785,8 +2766,8 @@ public static extern int b3GetLinkState(ref b3PhysicsClientHandle__ physClient, ///rayToWorldX: double ///rayToWorldY: double ///rayToWorldZ: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PickBody")] -public static extern System.IntPtr b3PickBody(ref b3PhysicsClientHandle__ physClient, double rayFromWorldX, double rayFromWorldY, double rayFromWorldZ, double rayToWorldX, double rayToWorldY, double rayToWorldZ) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PickBody")] +public static extern System.IntPtr b3PickBody(System.IntPtr physClient, double rayFromWorldX, double rayFromWorldY, double rayFromWorldZ, double rayToWorldX, double rayToWorldY, double rayToWorldZ) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* @@ -2797,14 +2778,14 @@ public static extern System.IntPtr b3PickBody(ref b3PhysicsClientHandle__ physC ///rayToWorldX: double ///rayToWorldY: double ///rayToWorldZ: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3MovePickedBody")] -public static extern System.IntPtr b3MovePickedBody(ref b3PhysicsClientHandle__ physClient, double rayFromWorldX, double rayFromWorldY, double rayFromWorldZ, double rayToWorldX, double rayToWorldY, double rayToWorldZ) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3MovePickedBody")] +public static extern System.IntPtr b3MovePickedBody(System.IntPtr physClient, double rayFromWorldX, double rayFromWorldY, double rayFromWorldZ, double rayToWorldX, double rayToWorldY, double rayToWorldZ) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RemovePickingConstraint")] -public static extern System.IntPtr b3RemovePickingConstraint(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RemovePickingConstraint")] +public static extern System.IntPtr b3RemovePickingConstraint(System.IntPtr physClient) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* @@ -2815,35 +2796,35 @@ public static extern System.IntPtr b3RemovePickingConstraint(ref b3PhysicsClien ///rayToWorldX: double ///rayToWorldY: double ///rayToWorldZ: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateRaycastCommandInit")] -public static extern System.IntPtr b3CreateRaycastCommandInit(ref b3PhysicsClientHandle__ physClient, double rayFromWorldX, double rayFromWorldY, double rayFromWorldZ, double rayToWorldX, double rayToWorldY, double rayToWorldZ) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateRaycastCommandInit")] +public static extern System.IntPtr b3CreateRaycastCommandInit(System.IntPtr physClient, double rayFromWorldX, double rayFromWorldY, double rayFromWorldZ, double rayToWorldX, double rayToWorldY, double rayToWorldZ) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateRaycastBatchCommandInit")] -public static extern System.IntPtr b3CreateRaycastBatchCommandInit(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateRaycastBatchCommandInit")] +public static extern System.IntPtr b3CreateRaycastBatchCommandInit(System.IntPtr physClient) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///rayFromWorld: double* ///rayToWorld: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RaycastBatchAddRay")] -public static extern void b3RaycastBatchAddRay(ref b3SharedMemoryCommandHandle__ commandHandle, ref double rayFromWorld, ref double rayToWorld) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RaycastBatchAddRay")] +public static extern void b3RaycastBatchAddRay(System.IntPtr commandHandle, ref double rayFromWorld, ref double rayToWorld) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///raycastInfo: b3RaycastInformation* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetRaycastInformation")] -public static extern void b3GetRaycastInformation(ref b3PhysicsClientHandle__ physClient, ref b3RaycastInformation raycastInfo) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetRaycastInformation")] +public static extern void b3GetRaycastInformation(System.IntPtr physClient, ref b3RaycastInformation raycastInfo) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ApplyExternalForceCommandInit")] -public static extern System.IntPtr b3ApplyExternalForceCommandInit(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ApplyExternalForceCommandInit")] +public static extern System.IntPtr b3ApplyExternalForceCommandInit(System.IntPtr physClient) ; /// Return Type: void @@ -2853,8 +2834,8 @@ public static extern System.IntPtr b3ApplyExternalForceCommandInit(ref b3Physic ///force: double* ///position: double* ///flags: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ApplyExternalForce")] -public static extern void b3ApplyExternalForce(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueId, int linkId, ref double force, ref double position, int flags) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ApplyExternalForce")] +public static extern void b3ApplyExternalForce(System.IntPtr commandHandle, int bodyUniqueId, int linkId, ref double force, ref double position, int flags) ; /// Return Type: void @@ -2863,232 +2844,232 @@ public static extern void b3ApplyExternalForce(ref b3SharedMemoryCommandHandle_ ///linkId: int ///torque: double* ///flags: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ApplyExternalTorque")] -public static extern void b3ApplyExternalTorque(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueId, int linkId, ref double torque, int flags) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ApplyExternalTorque")] +public static extern void b3ApplyExternalTorque(System.IntPtr commandHandle, int bodyUniqueId, int linkId, ref double torque, int flags) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadBunnyCommandInit")] -public static extern System.IntPtr b3LoadBunnyCommandInit(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadBunnyCommandInit")] +public static extern System.IntPtr b3LoadBunnyCommandInit(System.IntPtr physClient) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///scale: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadBunnySetScale")] -public static extern int b3LoadBunnySetScale(ref b3SharedMemoryCommandHandle__ commandHandle, double scale) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadBunnySetScale")] +public static extern int b3LoadBunnySetScale(System.IntPtr commandHandle, double scale) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///mass: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadBunnySetMass")] -public static extern int b3LoadBunnySetMass(ref b3SharedMemoryCommandHandle__ commandHandle, double mass) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadBunnySetMass")] +public static extern int b3LoadBunnySetMass(System.IntPtr commandHandle, double mass) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///collisionMargin: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadBunnySetCollisionMargin")] -public static extern int b3LoadBunnySetCollisionMargin(ref b3SharedMemoryCommandHandle__ commandHandle, double collisionMargin) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadBunnySetCollisionMargin")] +public static extern int b3LoadBunnySetCollisionMargin(System.IntPtr commandHandle, double collisionMargin) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestVREventsCommandInit")] -public static extern System.IntPtr b3RequestVREventsCommandInit(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestVREventsCommandInit")] +public static extern System.IntPtr b3RequestVREventsCommandInit(System.IntPtr physClient) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///deviceTypeFilter: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3VREventsSetDeviceTypeFilter")] -public static extern void b3VREventsSetDeviceTypeFilter(ref b3SharedMemoryCommandHandle__ commandHandle, int deviceTypeFilter) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3VREventsSetDeviceTypeFilter")] +public static extern void b3VREventsSetDeviceTypeFilter(System.IntPtr commandHandle, int deviceTypeFilter) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///vrEventsData: b3VREventsData* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetVREventsData")] -public static extern void b3GetVREventsData(ref b3PhysicsClientHandle__ physClient, ref b3VREventsData vrEventsData) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetVREventsData")] +public static extern void b3GetVREventsData(System.IntPtr physClient, ref b3VREventsData vrEventsData) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetVRCameraStateCommandInit")] -public static extern System.IntPtr b3SetVRCameraStateCommandInit(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetVRCameraStateCommandInit")] +public static extern System.IntPtr b3SetVRCameraStateCommandInit(System.IntPtr physClient) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///rootPos: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetVRCameraRootPosition")] -public static extern int b3SetVRCameraRootPosition(ref b3SharedMemoryCommandHandle__ commandHandle, ref double rootPos) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetVRCameraRootPosition")] +public static extern int b3SetVRCameraRootPosition(System.IntPtr commandHandle, ref double rootPos) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///rootOrn: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetVRCameraRootOrientation")] -public static extern int b3SetVRCameraRootOrientation(ref b3SharedMemoryCommandHandle__ commandHandle, ref double rootOrn) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetVRCameraRootOrientation")] +public static extern int b3SetVRCameraRootOrientation(System.IntPtr commandHandle, ref double rootOrn) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///objectUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetVRCameraTrackingObject")] -public static extern int b3SetVRCameraTrackingObject(ref b3SharedMemoryCommandHandle__ commandHandle, int objectUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetVRCameraTrackingObject")] +public static extern int b3SetVRCameraTrackingObject(System.IntPtr commandHandle, int objectUniqueId) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///flag: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetVRCameraTrackingObjectFlag")] -public static extern int b3SetVRCameraTrackingObjectFlag(ref b3SharedMemoryCommandHandle__ commandHandle, int flag) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetVRCameraTrackingObjectFlag")] +public static extern int b3SetVRCameraTrackingObjectFlag(System.IntPtr commandHandle, int flag) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestKeyboardEventsCommandInit")] -public static extern System.IntPtr b3RequestKeyboardEventsCommandInit(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestKeyboardEventsCommandInit")] +public static extern System.IntPtr b3RequestKeyboardEventsCommandInit(System.IntPtr physClient) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///keyboardEventsData: b3KeyboardEventsData* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetKeyboardEventsData")] -public static extern void b3GetKeyboardEventsData(ref b3PhysicsClientHandle__ physClient, ref b3KeyboardEventsData keyboardEventsData) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetKeyboardEventsData")] +public static extern void b3GetKeyboardEventsData(System.IntPtr physClient, ref b3KeyboardEventsData keyboardEventsData) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestMouseEventsCommandInit")] -public static extern System.IntPtr b3RequestMouseEventsCommandInit(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestMouseEventsCommandInit")] +public static extern System.IntPtr b3RequestMouseEventsCommandInit(System.IntPtr physClient) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///mouseEventsData: b3MouseEventsData* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetMouseEventsData")] -public static extern void b3GetMouseEventsData(ref b3PhysicsClientHandle__ physClient, ref b3MouseEventsData mouseEventsData) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetMouseEventsData")] +public static extern void b3GetMouseEventsData(System.IntPtr physClient, ref b3MouseEventsData mouseEventsData) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3StateLoggingCommandInit")] -public static extern System.IntPtr b3StateLoggingCommandInit(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3StateLoggingCommandInit")] +public static extern System.IntPtr b3StateLoggingCommandInit(System.IntPtr physClient) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///loggingType: int ///fileName: char* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3StateLoggingStart")] -public static extern int b3StateLoggingStart(ref b3SharedMemoryCommandHandle__ commandHandle, int loggingType, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3StateLoggingStart")] +public static extern int b3StateLoggingStart(System.IntPtr commandHandle, int loggingType, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///objectUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3StateLoggingAddLoggingObjectUniqueId")] -public static extern int b3StateLoggingAddLoggingObjectUniqueId(ref b3SharedMemoryCommandHandle__ commandHandle, int objectUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3StateLoggingAddLoggingObjectUniqueId")] +public static extern int b3StateLoggingAddLoggingObjectUniqueId(System.IntPtr commandHandle, int objectUniqueId) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///maxLogDof: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3StateLoggingSetMaxLogDof")] -public static extern int b3StateLoggingSetMaxLogDof(ref b3SharedMemoryCommandHandle__ commandHandle, int maxLogDof) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3StateLoggingSetMaxLogDof")] +public static extern int b3StateLoggingSetMaxLogDof(System.IntPtr commandHandle, int maxLogDof) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///linkIndexA: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3StateLoggingSetLinkIndexA")] -public static extern int b3StateLoggingSetLinkIndexA(ref b3SharedMemoryCommandHandle__ commandHandle, int linkIndexA) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3StateLoggingSetLinkIndexA")] +public static extern int b3StateLoggingSetLinkIndexA(System.IntPtr commandHandle, int linkIndexA) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///linkIndexB: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3StateLoggingSetLinkIndexB")] -public static extern int b3StateLoggingSetLinkIndexB(ref b3SharedMemoryCommandHandle__ commandHandle, int linkIndexB) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3StateLoggingSetLinkIndexB")] +public static extern int b3StateLoggingSetLinkIndexB(System.IntPtr commandHandle, int linkIndexB) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///bodyAUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3StateLoggingSetBodyAUniqueId")] -public static extern int b3StateLoggingSetBodyAUniqueId(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyAUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3StateLoggingSetBodyAUniqueId")] +public static extern int b3StateLoggingSetBodyAUniqueId(System.IntPtr commandHandle, int bodyAUniqueId) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///bodyBUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3StateLoggingSetBodyBUniqueId")] -public static extern int b3StateLoggingSetBodyBUniqueId(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyBUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3StateLoggingSetBodyBUniqueId")] +public static extern int b3StateLoggingSetBodyBUniqueId(System.IntPtr commandHandle, int bodyBUniqueId) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///deviceTypeFilter: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3StateLoggingSetDeviceTypeFilter")] -public static extern int b3StateLoggingSetDeviceTypeFilter(ref b3SharedMemoryCommandHandle__ commandHandle, int deviceTypeFilter) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3StateLoggingSetDeviceTypeFilter")] +public static extern int b3StateLoggingSetDeviceTypeFilter(System.IntPtr commandHandle, int deviceTypeFilter) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///logFlags: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3StateLoggingSetLogFlags")] -public static extern int b3StateLoggingSetLogFlags(ref b3SharedMemoryCommandHandle__ commandHandle, int logFlags) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3StateLoggingSetLogFlags")] +public static extern int b3StateLoggingSetLogFlags(System.IntPtr commandHandle, int logFlags) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusLoggingUniqueId")] -public static extern int b3GetStatusLoggingUniqueId(ref b3SharedMemoryStatusHandle__ statusHandle) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusLoggingUniqueId")] +public static extern int b3GetStatusLoggingUniqueId(System.IntPtr statusHandle) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///loggingUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3StateLoggingStop")] -public static extern int b3StateLoggingStop(ref b3SharedMemoryCommandHandle__ commandHandle, int loggingUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3StateLoggingStop")] +public static extern int b3StateLoggingStop(System.IntPtr commandHandle, int loggingUniqueId) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///name: char* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ProfileTimingCommandInit")] -public static extern System.IntPtr b3ProfileTimingCommandInit(ref b3PhysicsClientHandle__ physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string name) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ProfileTimingCommandInit")] +public static extern System.IntPtr b3ProfileTimingCommandInit(System.IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string name) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///duration: int - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetProfileTimingDuractionInMicroSeconds")] -public static extern void b3SetProfileTimingDuractionInMicroSeconds(ref b3SharedMemoryCommandHandle__ commandHandle, int duration) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetProfileTimingDuractionInMicroSeconds")] +public static extern void b3SetProfileTimingDuractionInMicroSeconds(System.IntPtr commandHandle, int duration) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///timeOutInSeconds: double - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetTimeOut")] -public static extern void b3SetTimeOut(ref b3PhysicsClientHandle__ physClient, double timeOutInSeconds) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetTimeOut")] +public static extern void b3SetTimeOut(System.IntPtr physClient, double timeOutInSeconds) ; /// Return Type: double ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetTimeOut")] -public static extern double b3GetTimeOut(ref b3PhysicsClientHandle__ physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetTimeOut")] +public static extern double b3GetTimeOut(System.IntPtr physClient) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///path: char* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetAdditionalSearchPath")] -public static extern System.IntPtr b3SetAdditionalSearchPath(ref b3PhysicsClientHandle__ physClient, System.IntPtr path) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetAdditionalSearchPath")] +public static extern System.IntPtr b3SetAdditionalSearchPath(System.IntPtr physClient, System.IntPtr path) ; /// Return Type: void @@ -3098,7 +3079,7 @@ public static extern System.IntPtr b3SetAdditionalSearchPath(ref b3PhysicsClien ///ornB: double* ///outPos: double* ///outOrn: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3MultiplyTransforms")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3MultiplyTransforms")] public static extern void b3MultiplyTransforms(ref double posA, ref double ornA, ref double posB, ref double ornB, ref double outPos, ref double outOrn) ; @@ -3107,7 +3088,7 @@ public static extern void b3MultiplyTransforms(ref double posA, ref double ornA ///orn: double* ///outPos: double* ///outOrn: double* - [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InvertTransform")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InvertTransform")] public static extern void b3InvertTransform(ref double pos, ref double orn, ref double outPos, ref double outOrn) ; } diff --git a/setup.py b/setup.py index ecd208318..6f6b16fcb 100644 --- a/setup.py +++ b/setup.py @@ -70,6 +70,7 @@ sources = ["examples/pybullet/pybullet.c"]\ +["examples/SharedMemory/PhysicsClientUDP_C_API.cpp"]\ +["examples/SharedMemory/PhysicsClientTCP.cpp"]\ +["examples/SharedMemory/PhysicsClientTCP_C_API.cpp"]\ ++["examples/SharedMemory/b3PluginManager.cpp"]\ +["examples/Utils/b3ResourcePath.cpp"]\ +["examples/Utils/RobotLoggingUtil.cpp"]\ +["examples/Utils/ChromeTraceUtil.cpp"]\ @@ -440,7 +441,7 @@ print("-----") setup( name = 'pybullet', - version='1.4.5', + version='1.4.6', description='Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning', long_description='pybullet is an easy to use Python module for physics simulation, robotics and deep reinforcement learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.', url='https://github.com/bulletphysics/bullet3', diff --git a/src/Bullet3Collision/BroadPhaseCollision/b3DynamicBvh.cpp b/src/Bullet3Collision/BroadPhaseCollision/b3DynamicBvh.cpp index 16991bc04..0f04efe33 100644 --- a/src/Bullet3Collision/BroadPhaseCollision/b3DynamicBvh.cpp +++ b/src/Bullet3Collision/BroadPhaseCollision/b3DynamicBvh.cpp @@ -227,26 +227,59 @@ static void b3FetchLeaves(b3DynamicBvh* pdbvt, } } -// -static void b3Split( const b3NodeArray& leaves, - b3NodeArray& left, - b3NodeArray& right, +static bool b3LeftOfAxis( const b3DbvtNode* node, + const b3Vector3& org, + const b3Vector3& axis) +{ + return b3Dot(axis,node->volume.Center()-org) <= 0; +} + +// Partitions leaves such that leaves[0, n) are on the +// left of axis, and leaves[n, count) are on the right +// of axis. returns N. +static int b3Split( b3DbvtNode** leaves, + int count, const b3Vector3& org, const b3Vector3& axis) { - left.resize(0); - right.resize(0); - for(int i=0,ni=leaves.size();ivolume.Center()-org)<0) - left.push_back(leaves[i]); - else - right.push_back(leaves[i]); + while(begin!=end && b3LeftOfAxis(leaves[begin],org,axis)) + { + ++begin; + } + + if(begin==end) + { + break; + } + + while(begin!=end && !b3LeftOfAxis(leaves[end-1],org,axis)) + { + --end; + } + + if(begin==end) + { + break; + } + + // swap out of place nodes + --end; + b3DbvtNode* temp=leaves[begin]; + leaves[begin]=leaves[end]; + leaves[end]=temp; + ++begin; } + + return begin; } // -static b3DbvtVolume b3Bounds( const b3NodeArray& leaves) +static b3DbvtVolume b3Bounds( b3DbvtNode** leaves, + int count) { #if B3_DBVT_MERGE_IMPL==B3_DBVT_IMPL_SSE B3_ATTRIBUTE_ALIGNED16(char locals[sizeof(b3DbvtVolume)]); @@ -255,7 +288,7 @@ static b3DbvtVolume b3Bounds( const b3NodeArray& leaves) #else b3DbvtVolume volume=leaves[0]->volume; #endif - for(int i=1,ni=leaves.size();ivolume,volume); } @@ -264,15 +297,16 @@ static b3DbvtVolume b3Bounds( const b3NodeArray& leaves) // static void b3BottomUp( b3DynamicBvh* pdbvt, - b3NodeArray& leaves) + b3DbvtNode** leaves, + int count) { - while(leaves.size()>1) + while(count>1) { b3Scalar minsize=B3_INFINITY; int minidx[2]={-1,-1}; - for(int i=0;ivolume,leaves[j]->volume)); if(szparent = p; n[1]->parent = p; leaves[minidx[0]] = p; - leaves.swap(minidx[1],leaves.size()-1); - leaves.pop_back(); + leaves[minidx[1]] = leaves[count-1]; + --count; } } // static b3DbvtNode* b3TopDown(b3DynamicBvh* pdbvt, - b3NodeArray& leaves, + b3DbvtNode** leaves, + int count, int bu_treshold) { static const b3Vector3 axis[]={b3MakeVector3(1,0,0), b3MakeVector3(0,1,0), b3MakeVector3(0,0,1)}; - if(leaves.size()>1) + b3Assert(bu_treshold>1); + if(count>1) { - if(leaves.size()>bu_treshold) + if(count>bu_treshold) { - const b3DbvtVolume vol=b3Bounds(leaves); + const b3DbvtVolume vol=b3Bounds(leaves,count); const b3Vector3 org=vol.Center(); - b3NodeArray sets[2]; + int partition; int bestaxis=-1; - int bestmidp=leaves.size(); + int bestmidp=count; int splitcount[3][2]={{0,0},{0,0},{0,0}}; int i; - for( i=0;ivolume.Center()-org; for(int j=0;j<3;++j) @@ -336,29 +372,23 @@ static b3DbvtNode* b3TopDown(b3DynamicBvh* pdbvt, } if(bestaxis>=0) { - sets[0].reserve(splitcount[bestaxis][0]); - sets[1].reserve(splitcount[bestaxis][1]); - b3Split(leaves,sets[0],sets[1],org,axis[bestaxis]); + partition=b3Split(leaves,count,org,axis[bestaxis]); + b3Assert(partition!=0 && partition!=count); } else { - sets[0].reserve(leaves.size()/2+1); - sets[1].reserve(leaves.size()/2); - for(int i=0,ni=leaves.size();ichilds[0]=b3TopDown(pdbvt,sets[0],bu_treshold); - node->childs[1]=b3TopDown(pdbvt,sets[1],bu_treshold); + node->childs[0]=b3TopDown(pdbvt,&leaves[0],partition,bu_treshold); + node->childs[1]=b3TopDown(pdbvt,&leaves[partition],count-partition,bu_treshold); node->childs[0]->parent=node; node->childs[1]->parent=node; return(node); } else { - b3BottomUp(pdbvt,leaves); + b3BottomUp(pdbvt,leaves,count); return(leaves[0]); } } @@ -442,7 +472,7 @@ void b3DynamicBvh::optimizeBottomUp() b3NodeArray leaves; leaves.reserve(m_leaves); b3FetchLeaves(this,m_root,leaves); - b3BottomUp(this,leaves); + b3BottomUp(this,&leaves[0],leaves.size()); m_root=leaves[0]; } } @@ -455,7 +485,7 @@ void b3DynamicBvh::optimizeTopDown(int bu_treshold) b3NodeArray leaves; leaves.reserve(m_leaves); b3FetchLeaves(this,m_root,leaves); - m_root=b3TopDown(this,leaves,bu_treshold); + m_root=b3TopDown(this,&leaves[0],leaves.size(),bu_treshold); } } diff --git a/src/BulletCollision/BroadphaseCollision/btDbvt.cpp b/src/BulletCollision/BroadphaseCollision/btDbvt.cpp index 2ca20cdd8..d791d0741 100644 --- a/src/BulletCollision/BroadphaseCollision/btDbvt.cpp +++ b/src/BulletCollision/BroadphaseCollision/btDbvt.cpp @@ -229,25 +229,60 @@ static void fetchleaves(btDbvt* pdbvt, } // -static void split( const tNodeArray& leaves, - tNodeArray& left, - tNodeArray& right, +static bool leftOfAxis( const btDbvtNode* node, + const btVector3& org, + const btVector3& axis) +{ + return btDot(axis, node->volume.Center() - org) <= 0; +} + + +// Partitions leaves such that leaves[0, n) are on the +// left of axis, and leaves[n, count) are on the right +// of axis. returns N. +static int split( btDbvtNode** leaves, + int count, const btVector3& org, const btVector3& axis) { - left.resize(0); - right.resize(0); - for(int i=0,ni=leaves.size();ivolume.Center()-org)<0) - left.push_back(leaves[i]); - else - right.push_back(leaves[i]); + while(begin!=end && leftOfAxis(leaves[begin],org,axis)) + { + ++begin; + } + + if(begin==end) + { + break; + } + + while(begin!=end && !leftOfAxis(leaves[end-1],org,axis)) + { + --end; + } + + if(begin==end) + { + break; + } + + // swap out of place nodes + --end; + btDbvtNode* temp=leaves[begin]; + leaves[begin]=leaves[end]; + leaves[end]=temp; + ++begin; } + + return begin; } // -static btDbvtVolume bounds( const tNodeArray& leaves) +static btDbvtVolume bounds( btDbvtNode** leaves, + int count) { #if DBVT_MERGE_IMPL==DBVT_IMPL_SSE ATTRIBUTE_ALIGNED16(char locals[sizeof(btDbvtVolume)]); @@ -257,7 +292,7 @@ static btDbvtVolume bounds( const tNodeArray& leaves) #else btDbvtVolume volume=leaves[0]->volume; #endif - for(int i=1,ni=leaves.size();ivolume,volume); } @@ -266,15 +301,16 @@ static btDbvtVolume bounds( const tNodeArray& leaves) // static void bottomup( btDbvt* pdbvt, - tNodeArray& leaves) + btDbvtNode** leaves, + int count) { - while(leaves.size()>1) + while(count>1) { btScalar minsize=SIMD_INFINITY; int minidx[2]={-1,-1}; - for(int i=0;ivolume,leaves[j]->volume)); if(szparent = p; n[1]->parent = p; leaves[minidx[0]] = p; - leaves.swap(minidx[1],leaves.size()-1); - leaves.pop_back(); + leaves[minidx[1]] = leaves[count-1]; + --count; } } // static btDbvtNode* topdown(btDbvt* pdbvt, - tNodeArray& leaves, + btDbvtNode** leaves, + int count, int bu_treshold) { static const btVector3 axis[]={btVector3(1,0,0), btVector3(0,1,0), btVector3(0,0,1)}; - if(leaves.size()>1) + btAssert(bu_treshold>2); + if(count>1) { - if(leaves.size()>bu_treshold) + if(count>bu_treshold) { - const btDbvtVolume vol=bounds(leaves); + const btDbvtVolume vol=bounds(leaves,count); const btVector3 org=vol.Center(); - tNodeArray sets[2]; + int partition; int bestaxis=-1; - int bestmidp=leaves.size(); + int bestmidp=count; int splitcount[3][2]={{0,0},{0,0},{0,0}}; int i; - for( i=0;ivolume.Center()-org; for(int j=0;j<3;++j) @@ -338,29 +376,23 @@ static btDbvtNode* topdown(btDbvt* pdbvt, } if(bestaxis>=0) { - sets[0].reserve(splitcount[bestaxis][0]); - sets[1].reserve(splitcount[bestaxis][1]); - split(leaves,sets[0],sets[1],org,axis[bestaxis]); + partition=split(leaves,count,org,axis[bestaxis]); + btAssert(partition!=0 && partition!=count); } else { - sets[0].reserve(leaves.size()/2+1); - sets[1].reserve(leaves.size()/2); - for(int i=0,ni=leaves.size();ichilds[0]=topdown(pdbvt,sets[0],bu_treshold); - node->childs[1]=topdown(pdbvt,sets[1],bu_treshold); + node->childs[0]=topdown(pdbvt,&leaves[0],partition,bu_treshold); + node->childs[1]=topdown(pdbvt,&leaves[partition],count-partition,bu_treshold); node->childs[0]->parent=node; node->childs[1]->parent=node; return(node); } else { - bottomup(pdbvt,leaves); + bottomup(pdbvt,leaves,count); return(leaves[0]); } } @@ -444,7 +476,7 @@ void btDbvt::optimizeBottomUp() tNodeArray leaves; leaves.reserve(m_leaves); fetchleaves(this,m_root,leaves); - bottomup(this,leaves); + bottomup(this,&leaves[0],leaves.size()); m_root=leaves[0]; } } @@ -457,7 +489,7 @@ void btDbvt::optimizeTopDown(int bu_treshold) tNodeArray leaves; leaves.reserve(m_leaves); fetchleaves(this,m_root,leaves); - m_root=topdown(this,leaves,bu_treshold); + m_root=topdown(this,&leaves[0],leaves.size(),bu_treshold); } } diff --git a/src/BulletDynamics/Dynamics/btDynamicsWorld.h b/src/BulletDynamics/Dynamics/btDynamicsWorld.h index a9ed1978f..42d8fc0de 100644 --- a/src/BulletDynamics/Dynamics/btDynamicsWorld.h +++ b/src/BulletDynamics/Dynamics/btDynamicsWorld.h @@ -135,6 +135,11 @@ public: return m_solverInfo; } + const btContactSolverInfo& getSolverInfo() const + { + return m_solverInfo; + } + ///obsolete, use addAction instead. virtual void addVehicle(btActionInterface* vehicle) {(void)vehicle;} diff --git a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h index e5113ae6c..c0c132bbb 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h +++ b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h @@ -72,6 +72,11 @@ public: return m_multiBodies[mbIndex]; } + const btMultiBody* getMultiBody(int mbIndex) const + { + return m_multiBodies[mbIndex]; + } + virtual void addMultiBodyConstraint( btMultiBodyConstraint* constraint); virtual int getNumMultiBodyConstraints() const diff --git a/src/BulletInverseDynamics/IDMath.cpp b/src/BulletInverseDynamics/IDMath.cpp index 021217a17..ecd62f76d 100644 --- a/src/BulletInverseDynamics/IDMath.cpp +++ b/src/BulletInverseDynamics/IDMath.cpp @@ -69,7 +69,7 @@ idScalar maxAbsMat3x(const mat3x &m) { void mul(const mat33 &a, const mat3x &b, mat3x *result) { if (b.cols() != result->cols()) { - error_message("size missmatch. a.cols()= %d, b.cols()= %d\n", + error_message("size missmatch. b.cols()= %d, result->cols()= %d\n", static_cast(b.cols()), static_cast(result->cols())); abort(); } diff --git a/src/BulletInverseDynamics/details/MultiBodyTreeImpl.cpp b/src/BulletInverseDynamics/details/MultiBodyTreeImpl.cpp index 847e5c6c7..b35c55df6 100644 --- a/src/BulletInverseDynamics/details/MultiBodyTreeImpl.cpp +++ b/src/BulletInverseDynamics/details/MultiBodyTreeImpl.cpp @@ -1013,7 +1013,7 @@ int MultiBodyTree::MultiBodyImpl::getBodyDotJacobianRotU(const int body_index, int MultiBodyTree::MultiBodyImpl::getBodyJacobianTrans(const int body_index, mat3x* world_jac_trans) const{ CHECK_IF_BODY_INDEX_IS_VALID(body_index); const RigidBody &body = m_body_list[body_index]; - mul(body.m_body_T_world.transpose(), body.m_body_Jac_T,world_jac_trans); + mul(body.m_body_T_world.transpose(), body.m_body_Jac_T, world_jac_trans); return 0; } diff --git a/test/SharedMemory/CMakeLists.txt b/test/SharedMemory/CMakeLists.txt index 542a52bb3..0feab4306 100644 --- a/test/SharedMemory/CMakeLists.txt +++ b/test/SharedMemory/CMakeLists.txt @@ -21,6 +21,9 @@ ENDIF() IF (NOT WIN32) LINK_LIBRARIES( pthread ) + IF (NOT APPLE) + LINK_LIBRARIES(${DL}) + ENDIF() ENDIF() ADD_EXECUTABLE(Test_PhysicsClientServer @@ -39,6 +42,7 @@ ENDIF() ../../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 diff --git a/test/SharedMemory/premake4.lua b/test/SharedMemory/premake4.lua index 282cc31fc..85b74ccfb 100644 --- a/test/SharedMemory/premake4.lua +++ b/test/SharedMemory/premake4.lua @@ -177,6 +177,8 @@ project ("Test_PhysicsServerLoopBack") "../../examples/SharedMemory/PhysicsServerSharedMemory.h", "../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp", "../../examples/SharedMemory/PhysicsServerCommandProcessor.h", + "../../examples/SharedMemory/b3PluginManager.cpp", + "../../examples/SharedMemory/PhysicsDirect.cpp", "../../examples/SharedMemory/PhysicsLoopBack.cpp", "../../examples/SharedMemory/PhysicsLoopBack.h", "../../examples/SharedMemory/PhysicsLoopBackC_API.cpp", @@ -261,6 +263,7 @@ project ("Test_PhysicsServerLoopBack") "../../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/PhysicsClientC_API.cpp", @@ -370,6 +373,7 @@ project ("Test_PhysicsServerInProcessExampleBrowser") "../../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/PhysicsClientC_API.cpp",