diff --git a/docs/pybullet_quickstartguide.pdf b/docs/pybullet_quickstartguide.pdf index 9a96ab0e4..8412d6715 100644 Binary files a/docs/pybullet_quickstartguide.pdf and b/docs/pybullet_quickstartguide.pdf differ diff --git a/examples/CommonInterfaces/CommonExampleInterface.h b/examples/CommonInterfaces/CommonExampleInterface.h index 220f9a583..0bccb2dd5 100644 --- a/examples/CommonInterfaces/CommonExampleInterface.h +++ b/examples/CommonInterfaces/CommonExampleInterface.h @@ -55,7 +55,7 @@ public: virtual bool mouseButtonCallback(int button, int state, float x, float y)=0; virtual bool keyboardCallback(int key, int state)=0; - virtual void vrControllerMoveCallback(int controllerId, float pos[4], float orientation[4], float analogAxis) {} + virtual void vrControllerMoveCallback(int controllerId, float pos[4], float orientation[4], float analogAxis, float auxAnalogAxes[10]) {} virtual void vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orientation[4]){} virtual void vrHMDMoveCallback(int controllerId, float pos[4], float orientation[4]){} virtual void vrGenericTrackerMoveCallback(int controllerId, float pos[4], float orientation[4]){} diff --git a/examples/ExampleBrowser/CMakeLists.txt b/examples/ExampleBrowser/CMakeLists.txt index 01d0b5c18..efe7c084e 100644 --- a/examples/ExampleBrowser/CMakeLists.txt +++ b/examples/ExampleBrowser/CMakeLists.txt @@ -122,6 +122,8 @@ SET(ExtendedTutorialsSources ../ExtendedTutorials/SimpleBox.h ../ExtendedTutorials/MultipleBoxes.cpp ../ExtendedTutorials/MultipleBoxes.h + ../ExtendedTutorials/CompoundBoxes.cpp + ../ExtendedTutorials/CompoundBoxes.h ../ExtendedTutorials/SimpleCloth.cpp ../ExtendedTutorials/SimpleCloth.h ../ExtendedTutorials/SimpleJoint.cpp diff --git a/examples/ExampleBrowser/ExampleEntries.cpp b/examples/ExampleBrowser/ExampleEntries.cpp index 34d123283..24d0a1fd2 100644 --- a/examples/ExampleBrowser/ExampleEntries.cpp +++ b/examples/ExampleBrowser/ExampleEntries.cpp @@ -71,6 +71,7 @@ //Extended Tutorial Includes Added by Mobeen and Benelot #include "../ExtendedTutorials/SimpleBox.h" #include "../ExtendedTutorials/MultipleBoxes.h" +#include "../ExtendedTutorials/CompoundBoxes.h" #include "../ExtendedTutorials/SimpleJoint.h" #include "../ExtendedTutorials/SimpleCloth.h" #include "../ExtendedTutorials/Chain.h" @@ -322,6 +323,7 @@ static ExampleEntry gDefaultExamples[]= ExampleEntry(0,"Extended Tutorials"), ExampleEntry(1,"Simple Box", "Simplest possible demo creating a single box rigid body that falls under gravity", ET_SimpleBoxCreateFunc), ExampleEntry(1,"Multiple Boxes", "Add multiple box rigid bodies that fall under gravity", ET_MultipleBoxesCreateFunc), + ExampleEntry(1,"Compound Boxes", "Add multiple boxes to a single CompoundShape to form a simple rigid L-beam, that falls under gravity", ET_CompoundBoxesCreateFunc), ExampleEntry(1,"Simple Joint", "Create a single distance constraint between two box rigid bodies", ET_SimpleJointCreateFunc), ExampleEntry(1,"Simple Cloth", "Create a simple piece of cloth", ET_SimpleClothCreateFunc), ExampleEntry(1,"Simple Chain", "Create a simple chain using a pair of point2point/distance constraints. You may click and drag any box to see the chain respond.", ET_ChainCreateFunc), diff --git a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp index 6c7ac6be2..d0d14b200 100644 --- a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp +++ b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp @@ -377,6 +377,13 @@ void OpenGLExampleBrowser::registerFileImporter(const char* extension, CommonExa void OpenGLExampleBrowserVisualizerFlagCallback(int flag, bool enable) { + if (flag == COV_ENABLE_Y_AXIS_UP) + { + //either Y = up or Z + int upAxis = enable? 1:2; + s_app->setUpAxis(upAxis); + } + if (flag == COV_ENABLE_RENDERING) { gEnableRenderLoop = (enable!=0); diff --git a/examples/ExampleBrowser/main.cpp b/examples/ExampleBrowser/main.cpp index 07c168309..3847181b5 100644 --- a/examples/ExampleBrowser/main.cpp +++ b/examples/ExampleBrowser/main.cpp @@ -30,19 +30,16 @@ static OpenGLExampleBrowser* sExampleBrowser=0; static void cleanup(int signo) { - if (interrupted) { // this is the second time, we're hanging somewhere - // if (example) { - // example->abort(); - // } - + if (!interrupted) { // this is the second time, we're hanging somewhere b3Printf("Aborting and deleting SharedMemoryCommon object"); - sleep(1); delete sExampleBrowser; - sExampleBrowser = 0; + sleep(1); + sExampleBrowser = 0; errx(EXIT_FAILURE, "aborted example on signal %d", signo); } else { - b3Printf("no action"); + b3Printf("no action"); + exit(EXIT_FAILURE); } interrupted = true; warnx("caught signal %d", signo); diff --git a/examples/ExtendedTutorials/CompoundBoxes.cpp b/examples/ExtendedTutorials/CompoundBoxes.cpp new file mode 100644 index 000000000..3a67fc504 --- /dev/null +++ b/examples/ExtendedTutorials/CompoundBoxes.cpp @@ -0,0 +1,135 @@ +/* +Bullet Continuous Collision Detection and Physics Library +Copyright (c) 2015 Google Inc. http://bulletphysics.org + +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +*/ + + + +#include "CompoundBoxes.h" + +#include "btBulletDynamicsCommon.h" +#include "LinearMath/btVector3.h" +#include "LinearMath/btAlignedObjectArray.h" +#include "../CommonInterfaces/CommonRigidBodyBase.h" + + +struct CompoundBoxesExample : public CommonRigidBodyBase +{ + CompoundBoxesExample(struct GUIHelperInterface* helper) + :CommonRigidBodyBase(helper) + { + } + virtual ~CompoundBoxesExample(){} + virtual void initPhysics(); + virtual void renderScene(); + void resetCamera() + { + float dist = 41; + float pitch = -35; + float yaw = 52; + float targetPos[3]={0,0.46,0}; + m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]); + } +}; + +void CompoundBoxesExample::initPhysics() +{ + m_guiHelper->setUpAxis(1); + + createEmptyDynamicsWorld(); + + m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); + + if (m_dynamicsWorld->getDebugDrawer()) + m_dynamicsWorld->getDebugDrawer()->setDebugMode(btIDebugDraw::DBG_DrawWireframe+btIDebugDraw::DBG_DrawContactPoints); + + ///create a few basic rigid bodies + btBoxShape* groundShape = createBoxShape(btVector3(btScalar(50.),btScalar(50.),btScalar(50.))); + m_collisionShapes.push_back(groundShape); + + btTransform groundTransform; + groundTransform.setIdentity(); + groundTransform.setOrigin(btVector3(0,-50,0)); + { + btScalar mass(0.); + createRigidBody(mass,groundTransform,groundShape, btVector4(0,0,1,1)); + } + + + { + //create a few dynamic rigidbodies + // Re-using the same collision is better for memory usage and performance + btBoxShape* cube = createBoxShape(btVector3(0.5,0.5,0.5)); + m_collisionShapes.push_back(cube); + + // create a new compound shape for making an L-beam from `cube`s + btCompoundShape* compoundShape = new btCompoundShape(); + + btTransform transform; + + // add cubes in an L-beam fashion to the compound shape + transform.setIdentity(); + transform.setOrigin(btVector3(0, 0, 0)); + compoundShape->addChildShape(transform, cube); + + transform.setIdentity(); + transform.setOrigin(btVector3(0, -1, 0)); + compoundShape->addChildShape(transform, cube); + + transform.setIdentity(); + transform.setOrigin(btVector3(0, 0, 1)); + compoundShape->addChildShape(transform, cube); + + + btScalar masses[3]={1, 1, 1}; + btTransform principal; + btVector3 inertia; + compoundShape->calculatePrincipalAxisTransform(masses, principal, inertia); + + // new compund shape to store + btCompoundShape* compound2 = new btCompoundShape(); + m_collisionShapes.push_back(compound2); +#if 0 + // less efficient way to add the entire compund shape + // to a new compund shape as a child + compound2->addChildShape(principal.inverse(), compoundShape); +#else + // recompute the shift to make sure the compound shape is re-aligned + for (int i=0; i < compoundShape->getNumChildShapes(); i++) + compound2->addChildShape(compoundShape->getChildTransform(i) * principal.inverse(), + compoundShape->getChildShape(i)); +#endif + delete compoundShape; + + transform.setIdentity(); + transform.setOrigin(btVector3(0, 10, 0)); + createRigidBody(1.0, transform, compound2); + } + + m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); +} + + +void CompoundBoxesExample::renderScene() +{ + CommonRigidBodyBase::renderScene(); +} + + +CommonExampleInterface* ET_CompoundBoxesCreateFunc(CommonExampleOptions& options) +{ + return new CompoundBoxesExample(options.m_guiHelper); +} + + + diff --git a/examples/ExtendedTutorials/CompoundBoxes.h b/examples/ExtendedTutorials/CompoundBoxes.h new file mode 100644 index 000000000..a453d03e8 --- /dev/null +++ b/examples/ExtendedTutorials/CompoundBoxes.h @@ -0,0 +1,22 @@ +/* +Bullet Continuous Collision Detection and Physics Library +Copyright (c) 2015 Google Inc. http://bulletphysics.org + +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +*/ + +#ifndef ET_COMPOUND_BOXES_EXAMPLE_H +#define ET_COMPOUND_BOXES_EXAMPLE_H + +class CommonExampleInterface* ET_CompoundBoxesCreateFunc(struct CommonExampleOptions& options); + + +#endif //ET_COMPOUND_BOXES_EXAMPLE_H diff --git a/examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp b/examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp index a7cf426cd..ae7c13a1d 100644 --- a/examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp +++ b/examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp @@ -17,6 +17,10 @@ struct CachedObjResult static b3HashMap gCachedObjResults; static int gEnableFileCaching = 1; +int b3IsFileCachingEnabled() +{ + return gEnableFileCaching; +} void b3EnableFileCaching(int enable) { gEnableFileCaching = enable; diff --git a/examples/Importers/ImportObjDemo/LoadMeshFromObj.h b/examples/Importers/ImportObjDemo/LoadMeshFromObj.h index 4d23eea8d..9414987f4 100644 --- a/examples/Importers/ImportObjDemo/LoadMeshFromObj.h +++ b/examples/Importers/ImportObjDemo/LoadMeshFromObj.h @@ -6,6 +6,7 @@ struct GLInstanceGraphicsShape; #include"../../ThirdPartyLibs/Wavefront/tiny_obj_loader.h" +int b3IsFileCachingEnabled(); void b3EnableFileCaching(int enable); std::string LoadFromCachedOrFromObj( diff --git a/examples/SharedMemory/BodyJointInfoUtility.h b/examples/SharedMemory/BodyJointInfoUtility.h index decced5ba..6bf018808 100644 --- a/examples/SharedMemory/BodyJointInfoUtility.h +++ b/examples/SharedMemory/BodyJointInfoUtility.h @@ -34,8 +34,8 @@ template void addJointInfoFromMultiBodyData(const T* mb { { b3JointInfo info; - info.m_jointName = 0; - info.m_linkName = 0; + info.m_jointName[0] = 0; + info.m_linkName[0] = 0; info.m_flags = 0; info.m_jointIndex = link; info.m_qIndex = @@ -48,14 +48,16 @@ template void addJointInfoFromMultiBodyData(const T* mb b3Printf("mb->m_links[%d].m_linkName = %s\n", link, mb->m_links[link].m_linkName); } - info.m_linkName = strDup(mb->m_links[link].m_linkName); + strcpy(info.m_linkName,mb->m_links[link].m_linkName); + } if (mb->m_links[link].m_jointName) { if (verboseOutput) { b3Printf("mb->m_links[%d].m_jointName = %s\n", link, mb->m_links[link].m_jointName); } - info.m_jointName = strDup(mb->m_links[link].m_jointName); + strcpy(info.m_jointName,mb->m_links[link].m_jointName); + //info.m_jointName = strDup(mb->m_links[link].m_jointName); } info.m_jointType = mb->m_links[link].m_jointType; diff --git a/examples/SharedMemory/PhysicsClient.h b/examples/SharedMemory/PhysicsClient.h index 28b823008..e81f25bfc 100644 --- a/examples/SharedMemory/PhysicsClient.h +++ b/examples/SharedMemory/PhysicsClient.h @@ -66,6 +66,8 @@ public: virtual void getCachedRaycastHits(struct b3RaycastInformation* raycastHits) = 0; + virtual void getCachedMassMatrix(int dofCountCheck, double* massMatrix) = 0; + virtual void setTimeOut(double timeOutInSeconds) = 0; virtual double getTimeOut() const = 0; diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index d8c2fff7f..8a74f9769 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -325,6 +325,32 @@ B3_SHARED_API int b3LoadUrdfCommandSetStartOrientation(b3SharedMemoryCommandHand return -1; } +B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestPhysicsParamCommand(b3PhysicsClientHandle physClient) +{ + PhysicsClient* cl = (PhysicsClient* ) physClient; + b3Assert(cl); + b3Assert(cl->canSubmitCommand()); + struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); + b3Assert(command); + command->m_type = CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS; + command->m_updateFlags = 0; + return (b3SharedMemoryCommandHandle) command; +} + +B3_SHARED_API int b3GetStatusPhysicsSimulationParameters(b3SharedMemoryStatusHandle statusHandle,struct b3PhysicsSimulationParameters* params) +{ + const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle; + b3Assert(status); + b3Assert(status->m_type == CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS_COMPLETED); + if (status && status->m_type == CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS_COMPLETED) + { + *params = status->m_simulationParameterResultArgs; + return 1; + } + return 0; +} + + B3_SHARED_API b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient* ) physClient; @@ -352,7 +378,7 @@ B3_SHARED_API int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandH { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS); - command->m_physSimParamArgs.m_allowRealTimeSimulation = (enableRealTimeSimulation!=0); + command->m_physSimParamArgs.m_useRealTimeSimulation = (enableRealTimeSimulation!=0); command->m_updateFlags |= SIM_PARAM_UPDATE_REAL_TIME_SIMULATION; return 0; } @@ -395,15 +421,11 @@ B3_SHARED_API int b3PhysicsParamSetContactBreakingThreshold(b3SharedMemoryComman command->m_updateFlags |= SIM_PARAM_UPDATE_CONTACT_BREAKING_THRESHOLD; return 0; } + B3_SHARED_API int b3PhysicsParamSetMaxNumCommandsPer1ms(b3SharedMemoryCommandHandle commandHandle, int maxNumCmdPer1ms) { - struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; - b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS); - - command->m_physSimParamArgs.m_maxNumCmdPer1ms = maxNumCmdPer1ms; - command->m_updateFlags |= SIM_PARAM_MAX_CMD_PER_1MS; + //obsolete command return 0; - } B3_SHARED_API int b3PhysicsParamSetEnableFileCaching(b3SharedMemoryCommandHandle commandHandle, int enableFileCaching) @@ -1438,7 +1460,10 @@ B3_SHARED_API int b3CreateSensorEnableIMUForLink(b3SharedMemoryCommandHandle com B3_SHARED_API void b3DisconnectSharedMemory(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient* ) physClient; - cl->disconnectSharedMemory(); + if (cl) + { + cl->disconnectSharedMemory(); + } delete cl; } @@ -1777,6 +1802,23 @@ B3_SHARED_API void b3CustomCommandLoadPlugin(b3SharedMemoryCommandHandle command } } +B3_SHARED_API void b3CustomCommandLoadPluginSetPostFix(b3SharedMemoryCommandHandle commandHandle, const char* postFix) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command->m_type == CMD_CUSTOM_COMMAND); + if (command->m_type == CMD_CUSTOM_COMMAND) + { + command->m_updateFlags |= CMD_CUSTOM_COMMAND_LOAD_PLUGIN_POSTFIX; + command->m_customCommandArgs.m_postFix[0] = 0; + + int len = strlen(postFix); + if (lenm_customCommandArgs.m_postFix, postFix); + } + } +} + B3_SHARED_API int b3GetStatusPluginCommandResult(b3SharedMemoryStatusHandle statusHandle) @@ -3377,6 +3419,48 @@ B3_SHARED_API int b3GetStatusJacobian(b3SharedMemoryStatusHandle statusHandle, i return true; } +B3_SHARED_API b3SharedMemoryCommandHandle b3CalculateMassMatrixCommandInit(b3PhysicsClientHandle physClient, int bodyIndex, const double* jointPositionsQ) +{ + PhysicsClient* cl = (PhysicsClient*)physClient; + b3Assert(cl); + b3Assert(cl->canSubmitCommand()); + struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); + b3Assert(command); + + command->m_type = CMD_CALCULATE_MASS_MATRIX; + command->m_updateFlags = 0; + int numJoints = cl->getNumJoints(bodyIndex); + for (int i = 0; i < numJoints; i++) + { + command->m_calculateMassMatrixArguments.m_jointPositionsQ[i] = jointPositionsQ[i]; + } + + return (b3SharedMemoryCommandHandle)command; +} + + +B3_SHARED_API int b3GetStatusMassMatrix(b3PhysicsClientHandle physClient, b3SharedMemoryStatusHandle statusHandle, int* dofCount, double* massMatrix) +{ + PhysicsClient* cl = (PhysicsClient*)physClient; + b3Assert(cl); + + const SharedMemoryStatus* status = (const SharedMemoryStatus*)statusHandle; + btAssert(status->m_type == CMD_CALCULATED_MASS_MATRIX_COMPLETED); + if (status->m_type != CMD_CALCULATED_MASS_MATRIX_COMPLETED) + return false; + + if (dofCount) + { + *dofCount = status->m_massMatrixResultArgs.m_dofCount; + } + if (massMatrix) + { + cl->getCachedMassMatrix(status->m_massMatrixResultArgs.m_dofCount, massMatrix); + } + + return true; +} + ///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/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index d18a547fe..54189dafa 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -63,6 +63,7 @@ B3_SHARED_API int b3GetStatusType(b3SharedMemoryStatusHandle statusHandle); ///Plugin system, load and unload a plugin, execute a command B3_SHARED_API b3SharedMemoryCommandHandle b3CreateCustomCommand(b3PhysicsClientHandle physClient); B3_SHARED_API void b3CustomCommandLoadPlugin(b3SharedMemoryCommandHandle commandHandle, const char* pluginPath); +B3_SHARED_API void b3CustomCommandLoadPluginSetPostFix(b3SharedMemoryCommandHandle commandHandle, const char* postFix); B3_SHARED_API int b3GetStatusPluginUniqueId(b3SharedMemoryStatusHandle statusHandle); B3_SHARED_API int b3GetStatusPluginCommandResult(b3SharedMemoryStatusHandle statusHandle); @@ -262,14 +263,10 @@ B3_SHARED_API int b3PhysicsParamSetTimeStep(b3SharedMemoryCommandHandle commandH B3_SHARED_API int b3PhysicsParamSetDefaultContactERP(b3SharedMemoryCommandHandle commandHandle, double defaultContactERP); B3_SHARED_API int b3PhysicsParamSetDefaultNonContactERP(b3SharedMemoryCommandHandle commandHandle, double defaultNonContactERP); B3_SHARED_API int b3PhysicsParamSetDefaultFrictionERP(b3SharedMemoryCommandHandle commandHandle, double frictionERP); - B3_SHARED_API int b3PhysicsParamSetNumSubSteps(b3SharedMemoryCommandHandle commandHandle, int numSubSteps); B3_SHARED_API int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandHandle commandHandle, int enableRealTimeSimulation); B3_SHARED_API int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHandle, int numSolverIterations); B3_SHARED_API int b3PhysicsParamSetCollisionFilterMode(b3SharedMemoryCommandHandle commandHandle, int filterMode); - - - B3_SHARED_API int b3PhysicsParamSetUseSplitImpulse(b3SharedMemoryCommandHandle commandHandle, int useSplitImpulse); B3_SHARED_API int b3PhysicsParamSetSplitImpulsePenetrationThreshold(b3SharedMemoryCommandHandle commandHandle, double splitImpulsePenetrationThreshold); B3_SHARED_API int b3PhysicsParamSetContactBreakingThreshold(b3SharedMemoryCommandHandle commandHandle, double contactBreakingThreshold); @@ -278,6 +275,9 @@ B3_SHARED_API int b3PhysicsParamSetEnableFileCaching(b3SharedMemoryCommandHandle B3_SHARED_API int b3PhysicsParamSetRestitutionVelocityThreshold(b3SharedMemoryCommandHandle commandHandle, double restitutionVelocityThreshold); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestPhysicsParamCommand(b3PhysicsClientHandle physClient); +B3_SHARED_API int b3GetStatusPhysicsSimulationParameters(b3SharedMemoryStatusHandle statusHandle,struct b3PhysicsSimulationParameters* params); + //b3PhysicsParamSetInternalSimFlags is for internal/temporary/easter-egg/experimental demo purposes //Use at own risk: magic things may or my not happen when calling this API @@ -310,19 +310,22 @@ B3_SHARED_API void b3LoadMJCFCommandSetFlags(b3SharedMemoryCommandHandle command ///compute the forces to achieve an acceleration, given a state q and qdot using inverse dynamics B3_SHARED_API b3SharedMemoryCommandHandle b3CalculateInverseDynamicsCommandInit(b3PhysicsClientHandle physClient, int bodyIndex, const double* jointPositionsQ, const double* jointVelocitiesQdot, const double* jointAccelerations); - B3_SHARED_API int b3GetStatusInverseDynamicsJointForces(b3SharedMemoryStatusHandle statusHandle, int* bodyUniqueId, int* dofCount, double* jointForces); 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, int* dofCount, double* linearJacobian, double* angularJacobian); +B3_SHARED_API b3SharedMemoryCommandHandle b3CalculateMassMatrixCommandInit(b3PhysicsClientHandle physClient, int bodyIndex, const double* jointPositionsQ); +///the mass matrix is stored in column-major layout of size dofCount*dofCount +B3_SHARED_API int b3GetStatusMassMatrix(b3PhysicsClientHandle physClient, b3SharedMemoryStatusHandle statusHandle, int* dofCount, double* massMatrix); + + ///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); B3_SHARED_API void b3CalculateInverseKinematicsAddTargetPurePosition(b3SharedMemoryCommandHandle commandHandle, int endEffectorLinkIndex, const double targetPosition[/*3*/]); diff --git a/examples/SharedMemory/PhysicsClientSharedMemory.cpp b/examples/SharedMemory/PhysicsClientSharedMemory.cpp index 94c73f5f2..050a9a257 100644 --- a/examples/SharedMemory/PhysicsClientSharedMemory.cpp +++ b/examples/SharedMemory/PhysicsClientSharedMemory.cpp @@ -47,7 +47,7 @@ struct PhysicsClientSharedMemoryInternalData { btAlignedObjectArray m_cachedVREvents; btAlignedObjectArray m_cachedKeyboardEvents; btAlignedObjectArray m_cachedMouseEvents; - + btAlignedObjectArray m_cachedMassMatrix; btAlignedObjectArray m_raycastHits; btAlignedObjectArray m_bodyIdsRequestInfo; @@ -108,8 +108,8 @@ bool PhysicsClientSharedMemory::getBodyInfo(int bodyUniqueId, struct b3BodyInfo& if (bodyJointsPtr && *bodyJointsPtr) { BodyJointInfoCache* bodyJoints = *bodyJointsPtr; - info.m_baseName = bodyJoints->m_baseName.c_str(); - info.m_bodyName = bodyJoints->m_bodyName.c_str(); + strcpy(info.m_baseName,bodyJoints->m_baseName.c_str()); + strcpy(info.m_bodyName,bodyJoints->m_bodyName.c_str()); return true; } @@ -234,16 +234,6 @@ void PhysicsClientSharedMemory::resetData() if (bodyJointsPtr && *bodyJointsPtr) { BodyJointInfoCache* bodyJoints = *bodyJointsPtr; - for (int j=0;jm_jointInfo.size();j++) { - if (bodyJoints->m_jointInfo[j].m_jointName) - { - free(bodyJoints->m_jointInfo[j].m_jointName); - } - if (bodyJoints->m_jointInfo[j].m_linkName) - { - free(bodyJoints->m_jointInfo[j].m_linkName); - } - } delete (*bodyJointsPtr); } } @@ -392,8 +382,8 @@ void PhysicsClientSharedMemory::processBodyJointInfo(int bodyUniqueId, const Sha template void addJointInfoFromConstraint(int linkIndex, const T* con, U* bodyJoints, bool verboseOutput) { b3JointInfo info; - info.m_jointName = 0; - info.m_linkName = 0; + info.m_jointName[0] = 0; + info.m_linkName[0] = 0; info.m_flags = 0; info.m_jointIndex = linkIndex; info.m_qIndex = linkIndex+7; @@ -402,7 +392,8 @@ template void addJointInfoFromConstraint(int linkIndex, if (con->m_typeConstraintData.m_name) { - info.m_jointName = strDup(con->m_typeConstraintData.m_name); + strcpy(info.m_jointName,con->m_typeConstraintData.m_name); + //info.m_linkName = strDup(con->m_typeConstraintData.m_name); } @@ -1219,6 +1210,25 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() { break; } + case CMD_CALCULATED_MASS_MATRIX_FAILED: + { + b3Warning("calculate mass matrix failed"); + break; + } + case CMD_CALCULATED_MASS_MATRIX_COMPLETED: + { + double* matrixData = (double*)&this->m_data->m_testBlock1->m_bulletStreamDataServerToClientRefactor[0]; + m_data->m_cachedMassMatrix.resize(serverCmd.m_massMatrixResultArgs.m_dofCount*serverCmd.m_massMatrixResultArgs.m_dofCount); + for (int i=0;im_cachedMassMatrix[i] = matrixData[i]; + } + break; + } + case CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS_COMPLETED: + { + break; + } default: { b3Error("Unknown server status %d\n", serverCmd.m_type); btAssert(0); @@ -1540,6 +1550,21 @@ void PhysicsClientSharedMemory::getCachedRaycastHits(struct b3RaycastInformation } +void PhysicsClientSharedMemory::getCachedMassMatrix(int dofCountCheck, double* massMatrix) +{ + int sz = dofCountCheck*dofCountCheck; + if (sz == m_data->m_cachedMassMatrix.size()) + { + for (int i=0;im_cachedMassMatrix[i]; + } + } +} + + + + void PhysicsClientSharedMemory::getCachedVisualShapeInformation(struct b3VisualShapeInformation* visualShapesInfo) { visualShapesInfo->m_numVisualShapes = m_data->m_cachedVisualShapes.size(); diff --git a/examples/SharedMemory/PhysicsClientSharedMemory.h b/examples/SharedMemory/PhysicsClientSharedMemory.h index 31c717c02..54bb48817 100644 --- a/examples/SharedMemory/PhysicsClientSharedMemory.h +++ b/examples/SharedMemory/PhysicsClientSharedMemory.h @@ -76,6 +76,8 @@ public: virtual void getCachedRaycastHits(struct b3RaycastInformation* raycastHits); + virtual void getCachedMassMatrix(int dofCountCheck, double* massMatrix); + virtual void setTimeOut(double timeOutInSeconds); virtual double getTimeOut() const; diff --git a/examples/SharedMemory/PhysicsDirect.cpp b/examples/SharedMemory/PhysicsDirect.cpp index 76d09dfe7..94922ff0d 100644 --- a/examples/SharedMemory/PhysicsDirect.cpp +++ b/examples/SharedMemory/PhysicsDirect.cpp @@ -40,7 +40,7 @@ struct PhysicsDirectInternalData btHashMap m_userConstraintInfoMap; char m_bulletStreamDataServerToClient[SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE]; - + btAlignedObjectArray m_cachedMassMatrix; int m_cachedCameraPixelsWidth; int m_cachedCameraPixelsHeight; btAlignedObjectArray m_cachedCameraPixelsRGBA; @@ -112,17 +112,6 @@ void PhysicsDirect::resetData() BodyJointInfoCache2** bodyJointsPtr = m_data->m_bodyJointMap.getAtIndex(i); if (bodyJointsPtr && *bodyJointsPtr) { - BodyJointInfoCache2* bodyJoints = *bodyJointsPtr; - for (int j = 0; jm_jointInfo.size(); j++) { - if (bodyJoints->m_jointInfo[j].m_jointName) - { - free(bodyJoints->m_jointInfo[j].m_jointName); - } - if (bodyJoints->m_jointInfo[j].m_linkName) - { - free(bodyJoints->m_jointInfo[j].m_linkName); - } - } delete (*bodyJointsPtr); } } @@ -962,6 +951,21 @@ void PhysicsDirect::postProcessStatus(const struct SharedMemoryStatus& serverCmd b3Warning("jacobian calculation failed"); break; } + case CMD_CALCULATED_MASS_MATRIX_FAILED: + { + b3Warning("calculate mass matrix failed"); + break; + } + case CMD_CALCULATED_MASS_MATRIX_COMPLETED: + { + double* matrixData = (double*)&m_data->m_bulletStreamDataServerToClient[0]; + m_data->m_cachedMassMatrix.resize(serverCmd.m_massMatrixResultArgs.m_dofCount*serverCmd.m_massMatrixResultArgs.m_dofCount); + for (int i=0;im_cachedMassMatrix[i] = matrixData[i]; + } + break; + } case CMD_ACTUAL_STATE_UPDATE_COMPLETED: { break; @@ -974,6 +978,10 @@ void PhysicsDirect::postProcessStatus(const struct SharedMemoryStatus& serverCmd { break; } + case CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS_COMPLETED: + { + break; + } default: { //b3Warning("Unknown server status type"); @@ -1085,8 +1093,8 @@ bool PhysicsDirect::getBodyInfo(int bodyUniqueId, struct b3BodyInfo& info) const if (bodyJointsPtr && *bodyJointsPtr) { BodyJointInfoCache2* bodyJoints = *bodyJointsPtr; - info.m_baseName = bodyJoints->m_baseName.c_str(); - info.m_bodyName = bodyJoints->m_bodyName.c_str(); + strcpy(info.m_baseName,bodyJoints->m_baseName.c_str()); + strcpy(info.m_bodyName ,bodyJoints->m_bodyName .c_str()); return true; } @@ -1231,6 +1239,18 @@ void PhysicsDirect::getCachedRaycastHits(struct b3RaycastInformation* raycastHit raycastHits->m_rayHits = raycastHits->m_numRayHits? &m_data->m_raycastHits[0] : 0; } +void PhysicsDirect::getCachedMassMatrix(int dofCountCheck, double* massMatrix) +{ + int sz = dofCountCheck*dofCountCheck; + if (sz == m_data->m_cachedMassMatrix.size()) + { + for (int i=0;im_cachedMassMatrix[i]; + } + } +} + void PhysicsDirect::setTimeOut(double timeOutInSeconds) { m_data->m_timeOutInSeconds = timeOutInSeconds; diff --git a/examples/SharedMemory/PhysicsDirect.h b/examples/SharedMemory/PhysicsDirect.h index 282a61732..a42ec01d8 100644 --- a/examples/SharedMemory/PhysicsDirect.h +++ b/examples/SharedMemory/PhysicsDirect.h @@ -99,6 +99,8 @@ public: virtual void getCachedRaycastHits(struct b3RaycastInformation* raycastHits); + virtual void getCachedMassMatrix(int dofCountCheck, double* massMatrix); + //the following APIs are for internal use for visualization: virtual bool connect(struct GUIHelperInterface* guiHelper); virtual void renderScene(); diff --git a/examples/SharedMemory/PhysicsLoopBack.cpp b/examples/SharedMemory/PhysicsLoopBack.cpp index 3067f2ace..e9880da7f 100644 --- a/examples/SharedMemory/PhysicsLoopBack.cpp +++ b/examples/SharedMemory/PhysicsLoopBack.cpp @@ -205,6 +205,11 @@ void PhysicsLoopBack::getCachedRaycastHits(struct b3RaycastInformation* raycastH return m_data->m_physicsClient->getCachedRaycastHits(raycastHits); } +void PhysicsLoopBack::getCachedMassMatrix(int dofCountCheck, double* massMatrix) +{ + m_data->m_physicsClient->getCachedMassMatrix(dofCountCheck,massMatrix); +} + void PhysicsLoopBack::setTimeOut(double timeOutInSeconds) { m_data->m_physicsClient->setTimeOut(timeOutInSeconds); diff --git a/examples/SharedMemory/PhysicsLoopBack.h b/examples/SharedMemory/PhysicsLoopBack.h index f83cd7234..44d54a40e 100644 --- a/examples/SharedMemory/PhysicsLoopBack.h +++ b/examples/SharedMemory/PhysicsLoopBack.h @@ -80,6 +80,8 @@ public: virtual void getCachedRaycastHits(struct b3RaycastInformation* raycastHits); + virtual void getCachedMassMatrix(int dofCountCheck, double* massMatrix); + virtual void setTimeOut(double timeOutInSeconds); virtual double getTimeOut() const; }; diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index f9e0cd6a9..4cc70b724 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -40,6 +40,11 @@ #include "../Utils/b3Clock.h" #include "b3PluginManager.h" + +#ifdef STATIC_LINK_VR_PLUGIN +#include "plugins/vrSyncPlugin/vrSyncPlugin.h" +#endif + #ifdef B3_ENABLE_TINY_AUDIO #include "../TinyAudio/b3SoundEngine.h" #endif @@ -355,7 +360,7 @@ struct CommandLogger case CMD_SEND_PHYSICS_SIMULATION_PARAMETERS: { fwrite((const char*)&command.m_updateFlags,sizeof(int), 1,m_file); - fwrite((const char*)&command.m_physSimParamArgs, sizeof(SendPhysicsSimulationParameters), 1,m_file); + fwrite((const char*)&command.m_physSimParamArgs, sizeof(b3PhysicsSimulationParameters), 1,m_file); break; } case CMD_REQUEST_CONTACT_POINT_INFORMATION: @@ -559,7 +564,7 @@ struct CommandLogPlayback cmd->m_physSimParamArgs = unused.m_physSimParamArgs; #else fread(&cmd->m_updateFlags,sizeof(int),1,m_file); - fread(&cmd->m_physSimParamArgs ,sizeof(SendPhysicsSimulationParameters),1,m_file); + fread(&cmd->m_physSimParamArgs ,sizeof(b3PhysicsSimulationParameters),1,m_file); #endif result = true; @@ -884,8 +889,18 @@ struct b3VRControllerEvents if (vrEvents[i].m_numMoveEvents) { m_vrEvents[controlledId].m_analogAxis = vrEvents[i].m_analogAxis; + for (int a=0;a<10;a++) + { + m_vrEvents[controlledId].m_auxAnalogAxis[a] = vrEvents[i].m_auxAnalogAxis[a]; + } + } else + { + m_vrEvents[controlledId].m_analogAxis = 0; + for (int a=0;a<10;a++) + { + m_vrEvents[controlledId].m_auxAnalogAxis[a] = 0; + } } - if (vrEvents[i].m_numMoveEvents+vrEvents[i].m_numButtonEvents) { m_vrEvents[controlledId].m_controllerId = vrEvents[i].m_controllerId; @@ -1435,7 +1450,7 @@ struct PhysicsServerCommandProcessorInternalData b3PluginManager m_pluginManager; - bool m_allowRealTimeSimulation; + bool m_useRealTimeSimulation; b3VRControllerEvents m_vrControllerEvents; @@ -1519,7 +1534,7 @@ struct PhysicsServerCommandProcessorInternalData PhysicsServerCommandProcessorInternalData(PhysicsCommandProcessorInterface* proc) :m_pluginManager(proc), - m_allowRealTimeSimulation(false), + m_useRealTimeSimulation(false), m_commandLogger(0), m_logPlayback(0), m_physicsDeltaTime(1./240.), @@ -1546,10 +1561,11 @@ struct PhysicsServerCommandProcessorInternalData { - //test to statically link a plugin - //#include "plugins/testPlugin/testplugin.h" //register static plugins: - //m_pluginManager.registerStaticLinkedPlugin("path", initPlugin, exitPlugin, executePluginCommand); +#ifdef STATIC_LINK_VR_PLUGIN + m_pluginManager.registerStaticLinkedPlugin("vrSyncPlugin", initPlugin_vrSyncPlugin, exitPlugin_vrSyncPlugin, executePluginCommand_vrSyncPlugin,preTickPluginCallback_vrSyncPlugin,0); +#endif //STATIC_LINK_VR_PLUGIN + } m_vrControllerEvents.init(); @@ -1699,7 +1715,6 @@ void logCallback(btDynamicsWorld *world, btScalar timeStep) bool isPreTick = false; proc->tickPlugins(timeStep, isPreTick); - } bool MyContactAddedCallback(btManifoldPoint& cp, const btCollisionObjectWrapper* colObj0Wrap,int partId0,int index0,const btCollisionObjectWrapper* colObj1Wrap,int partId1,int index1) @@ -1810,6 +1825,11 @@ void PhysicsServerCommandProcessor::processCollisionForces(btScalar timeStep) void PhysicsServerCommandProcessor::tickPlugins(btScalar timeStep, bool isPreTick) { m_data->m_pluginManager.tickPlugins(timeStep, isPreTick); + if (!isPreTick) + { + //clear events after each postTick, so we don't receive events multiple ticks + m_data->m_pluginManager.clearEvents(); + } } @@ -2993,7 +3013,7 @@ int PhysicsServerCommandProcessor::createBodyInfoStream(int bodyUniqueId, char* bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes ) { // BT_PROFILE("processCommand"); - + bool hasStatus = false; { @@ -5680,6 +5700,33 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm } break; } + + case CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS: + { + SharedMemoryStatus& serverCmd =serverStatusOut; + serverCmd.m_type = CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS_COMPLETED; + serverCmd.m_simulationParameterResultArgs.m_collisionFilterMode = m_data->m_broadphaseCollisionFilterCallback->m_filterMode; + serverCmd.m_simulationParameterResultArgs.m_contactBreakingThreshold = gContactBreakingThreshold; + serverCmd.m_simulationParameterResultArgs.m_defaultContactERP = m_data->m_dynamicsWorld->getSolverInfo().m_erp2; + serverCmd.m_simulationParameterResultArgs.m_defaultNonContactERP = m_data->m_dynamicsWorld->getSolverInfo().m_erp; + serverCmd.m_simulationParameterResultArgs.m_deltaTime = m_data->m_physicsDeltaTime; + serverCmd.m_simulationParameterResultArgs.m_enableFileCaching = b3IsFileCachingEnabled(); + serverCmd.m_simulationParameterResultArgs.m_frictionERP = m_data->m_dynamicsWorld->getSolverInfo().m_frictionERP; + btVector3 grav = m_data->m_dynamicsWorld->getGravity(); + serverCmd.m_simulationParameterResultArgs.m_gravityAcceleration[0] = grav[0]; + serverCmd.m_simulationParameterResultArgs.m_gravityAcceleration[1] = grav[1]; + serverCmd.m_simulationParameterResultArgs.m_gravityAcceleration[2] = grav[2]; + serverCmd.m_simulationParameterResultArgs.m_internalSimFlags = gInternalSimFlags; + serverCmd.m_simulationParameterResultArgs.m_numSimulationSubSteps = m_data->m_numSimulationSubSteps; + serverCmd.m_simulationParameterResultArgs.m_numSolverIterations = m_data->m_dynamicsWorld->getSolverInfo().m_numIterations; + serverCmd.m_simulationParameterResultArgs.m_restitutionVelocityThreshold = m_data->m_dynamicsWorld->getSolverInfo().m_restitutionVelocityThreshold; + serverCmd.m_simulationParameterResultArgs.m_splitImpulsePenetrationThreshold = m_data->m_dynamicsWorld->getSolverInfo().m_splitImpulsePenetrationThreshold; + serverCmd.m_simulationParameterResultArgs.m_useRealTimeSimulation = m_data->m_useRealTimeSimulation; + serverCmd.m_simulationParameterResultArgs.m_useSplitImpulse = m_data->m_dynamicsWorld->getSolverInfo().m_splitImpulse; + hasStatus = true; + break; + } + case CMD_SEND_PHYSICS_SIMULATION_PARAMETERS: { BT_PROFILE("CMD_SEND_PHYSICS_SIMULATION_PARAMETERS"); @@ -5690,7 +5737,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm } if (clientCmd.m_updateFlags & SIM_PARAM_UPDATE_REAL_TIME_SIMULATION) { - m_data->m_allowRealTimeSimulation = clientCmd.m_physSimParamArgs.m_allowRealTimeSimulation; + m_data->m_useRealTimeSimulation = (clientCmd.m_physSimParamArgs.m_useRealTimeSimulation!=0); } //see @@ -6707,6 +6754,61 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm hasStatus = true; break; } + case CMD_CALCULATE_MASS_MATRIX: + { + BT_PROFILE("CMD_CALCULATE_MASS_MATRIX"); + + SharedMemoryStatus& serverCmd = serverStatusOut; + serverCmd.m_type = CMD_CALCULATED_MASS_MATRIX_FAILED; + InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(clientCmd.m_calculateMassMatrixArguments.m_bodyUniqueId); + if (bodyHandle && bodyHandle->m_multiBody) + { + + btInverseDynamics::MultiBodyTree* tree = m_data->findOrCreateTree(bodyHandle->m_multiBody); + + if (tree) + { + int baseDofs = bodyHandle->m_multiBody->hasFixedBase() ? 0 : 6; + const int numDofs = bodyHandle->m_multiBody->getNumDofs(); + const int totDofs = numDofs + baseDofs; + btInverseDynamics::vecx q(totDofs); + btInverseDynamics::matxx massMatrix(totDofs, totDofs); + for (int i = 0; i < numDofs; i++) + { + q[i + baseDofs] = clientCmd.m_calculateMassMatrixArguments.m_jointPositionsQ[i]; + } + if (-1 != tree->calculateMassMatrix(q, &massMatrix)) + { + serverCmd.m_massMatrixResultArgs.m_dofCount = totDofs; + // Fill in the result into the shared memory. + double* sharedBuf = (double*)bufferServerToClient; + int sizeInBytes = totDofs*totDofs*sizeof(double); + if (sizeInBytes < bufferSizeInBytes) + { + for (int i = 0; i < (totDofs); ++i) + { + for (int j = 0; j < (totDofs); ++j) + { + int element = (totDofs) * i + j; + + sharedBuf[element] = massMatrix(i,j); + } + } + serverCmd.m_type = CMD_CALCULATED_MASS_MATRIX_COMPLETED; + } + } + + } + + } + else + { + serverCmd.m_type = CMD_CALCULATED_MASS_MATRIX_FAILED; + } + + hasStatus = true; + break; + } case CMD_APPLY_EXTERNAL_FORCE: { BT_PROFILE("CMD_APPLY_EXTERNAL_FORCE"); @@ -8027,7 +8129,13 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm if (clientCmd.m_updateFlags & CMD_CUSTOM_COMMAND_LOAD_PLUGIN) { //pluginPath could be registered or load from disk - int pluginUniqueId = m_data->m_pluginManager.loadPlugin(clientCmd.m_customCommandArgs.m_pluginPath); + const char* postFix = ""; + if (clientCmd.m_updateFlags & CMD_CUSTOM_COMMAND_LOAD_PLUGIN_POSTFIX) + { + postFix = clientCmd.m_customCommandArgs.m_postFix; + } + + int pluginUniqueId = m_data->m_pluginManager.loadPlugin(clientCmd.m_customCommandArgs.m_pluginPath, postFix); if (pluginUniqueId>=0) { serverCmd.m_customCommandResultArgs.m_pluginUniqueId = pluginUniqueId; @@ -8280,18 +8388,18 @@ double gSubStep = 0.f; void PhysicsServerCommandProcessor::enableRealTimeSimulation(bool enableRealTimeSim) { - m_data->m_allowRealTimeSimulation = enableRealTimeSim; + m_data->m_useRealTimeSimulation = enableRealTimeSim; } bool PhysicsServerCommandProcessor::isRealTimeSimulationEnabled() const { - return m_data->m_allowRealTimeSimulation; + return m_data->m_useRealTimeSimulation; } void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec,const struct b3VRControllerEvent* vrControllerEvents, int numVRControllerEvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents, const struct b3MouseEvent* mouseEvents, int numMouseEvents) { m_data->m_vrControllerEvents.addNewVREvents(vrControllerEvents,numVRControllerEvents); - + m_data->m_pluginManager.addEvents(vrControllerEvents, numVRControllerEvents, keyEvents, numKeyEvents, mouseEvents, numMouseEvents); for (int i=0;im_stateLoggers.size();i++) { @@ -8390,7 +8498,7 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec,const } } - if ((m_data->m_allowRealTimeSimulation) && m_data->m_guiHelper) + if ((m_data->m_useRealTimeSimulation) && m_data->m_guiHelper) { diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index 208eeafe4..3cf461ae5 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -1330,7 +1330,7 @@ public: btVector3 getRayTo(int x,int y); virtual void vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orientation[4]); - virtual void vrControllerMoveCallback(int controllerId, float pos[4], float orientation[4], float analogAxis); + virtual void vrControllerMoveCallback(int controllerId, float pos[4], float orientation[4], float analogAxis, float auxAnalogAxes[10]); virtual void vrHMDMoveCallback(int controllerId, float pos[4], float orientation[4]); virtual void vrGenericTrackerMoveCallback(int controllerId, float pos[4], float orientation[4]); @@ -2874,7 +2874,7 @@ void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int butt } -void PhysicsServerExample::vrControllerMoveCallback(int controllerId, float pos[4], float orn[4], float analogAxis) +void PhysicsServerExample::vrControllerMoveCallback(int controllerId, float pos[4], float orn[4], float analogAxis, float auxAnalogAxes[10]) { if (controllerId < 0 || controllerId >= MAX_VR_CONTROLLERS) @@ -2927,6 +2927,11 @@ void PhysicsServerExample::vrControllerMoveCallback(int controllerId, float pos[ m_args[0].m_vrControllerEvents[controllerId].m_orn[3] = trTotal.getRotation()[3]; m_args[0].m_vrControllerEvents[controllerId].m_numMoveEvents++; m_args[0].m_vrControllerEvents[controllerId].m_analogAxis = analogAxis; + for (int i=0;i<10;i++) + { + m_args[0].m_vrControllerEvents[controllerId].m_auxAnalogAxis[i] = auxAnalogAxes[i]; + } + m_args[0].m_csGUI->unlock(); } diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index b196d6c71..5a983647c 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -114,6 +114,7 @@ enum CustomCommandEnum CMD_CUSTOM_COMMAND_LOAD_PLUGIN=1, CMD_CUSTOM_COMMAND_UNLOAD_PLUGIN=2, CMD_CUSTOM_COMMAND_EXECUTE_PLUGIN_COMMAND=4, + CMD_CUSTOM_COMMAND_LOAD_PLUGIN_POSTFIX=8, }; struct b3CustomCommand @@ -121,6 +122,8 @@ struct b3CustomCommand int m_pluginUniqueId; b3PluginArguments m_arguments; char m_pluginPath[MAX_FILENAME_LENGTH]; + char m_postFix[MAX_FILENAME_LENGTH]; + }; struct b3CustomCommandResultArgs @@ -425,25 +428,6 @@ enum EnumSimParamInternalSimFlags ///Controlling a robot involves sending the desired state to its joint motor controllers. ///The control mode determines the state variables used for motor control. -struct SendPhysicsSimulationParameters -{ - double m_deltaTime; - double m_gravityAcceleration[3]; - int m_numSimulationSubSteps; - int m_numSolverIterations; - bool m_allowRealTimeSimulation; - int m_useSplitImpulse; - double m_splitImpulsePenetrationThreshold; - double m_contactBreakingThreshold; - int m_maxNumCmdPer1ms; - int m_internalSimFlags; - double m_defaultContactERP; - int m_collisionFilterMode; - int m_enableFileCaching; - double m_restitutionVelocityThreshold; - double m_defaultNonContactERP; - double m_frictionERP; -}; struct LoadBunnyArgs { @@ -638,6 +622,17 @@ struct CalculateJacobianResultArgs double m_angularJacobian[3*MAX_DEGREE_OF_FREEDOM]; }; +struct CalculateMassMatrixArgs +{ + int m_bodyUniqueId; + double m_jointPositionsQ[MAX_DEGREE_OF_FREEDOM]; +}; + +struct CalculateMassMatrixResultArgs +{ + int m_dofCount; +}; + enum EnumCalculateInverseKinematicsFlags { IK_HAS_TARGET_POSITION=1, @@ -957,7 +952,7 @@ struct SharedMemoryCommand struct ChangeDynamicsInfoArgs m_changeDynamicsInfoArgs; struct GetDynamicsInfoArgs m_getDynamicsInfoArgs; struct InitPoseArgs m_initPoseArgs; - struct SendPhysicsSimulationParameters m_physSimParamArgs; + struct b3PhysicsSimulationParameters m_physSimParamArgs; struct BulletDataStreamArgs m_dataStreamArguments; struct SendDesiredStateArgs m_sendDesiredStateCommandArgument; struct RequestActualStateArgs m_requestActualStateInformationCommandArgument; @@ -969,6 +964,7 @@ struct SharedMemoryCommand struct ExternalForceArgs m_externalForceArguments; struct CalculateInverseDynamicsArgs m_calculateInverseDynamicsArguments; struct CalculateJacobianArgs m_calculateJacobianArguments; + struct CalculateMassMatrixArgs m_calculateMassMatrixArguments; struct b3UserConstraint m_userConstraintArguments; struct RequestContactDataArgs m_requestContactPointArguments; struct RequestOverlappingObjectsArgs m_requestOverlappingObjectsArgs; @@ -1043,6 +1039,7 @@ struct SharedMemoryStatus struct RigidBodyCreateArgs m_rigidBodyCreateArgs; struct CalculateInverseDynamicsResultArgs m_inverseDynamicsResultArgs; struct CalculateJacobianResultArgs m_jacobianResultArgs; + struct CalculateMassMatrixResultArgs m_massMatrixResultArgs; struct SendContactDataArgs m_sendContactPointArgs; struct SendOverlappingObjectsArgs m_sendOverlappingObjectsArgs; struct CalculateInverseKinematicsResultArgs m_inverseKinematicsResultArgs; @@ -1063,7 +1060,7 @@ struct SharedMemoryStatus struct SendMouseEvents m_sendMouseEvents; struct b3LoadTextureResultArgs m_loadTextureResultArguments; struct b3CustomCommandResultArgs m_customCommandResultArgs; - + struct b3PhysicsSimulationParameters m_simulationParameterResultArgs; }; }; diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index 28b7ec5b1..3a02af8d4 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -5,7 +5,7 @@ ///increase the SHARED_MEMORY_MAGIC_NUMBER whenever incompatible changes are made in the structures ///my convention is year/month/day/rev -#define SHARED_MEMORY_MAGIC_NUMBER 201709260 +#define SHARED_MEMORY_MAGIC_NUMBER 201710050 //#define SHARED_MEMORY_MAGIC_NUMBER 201708270 //#define SHARED_MEMORY_MAGIC_NUMBER 201707140 //#define SHARED_MEMORY_MAGIC_NUMBER 201706015 @@ -43,6 +43,7 @@ enum EnumSharedMemoryClientCommand CMD_CALCULATE_INVERSE_DYNAMICS, CMD_CALCULATE_INVERSE_KINEMATICS, CMD_CALCULATE_JACOBIAN, + CMD_CALCULATE_MASS_MATRIX, CMD_USER_CONSTRAINT, CMD_REQUEST_CONTACT_POINT_INFORMATION, CMD_REQUEST_RAY_CAST_INTERSECTIONS, @@ -74,6 +75,7 @@ enum EnumSharedMemoryClientCommand CMD_CHANGE_TEXTURE, CMD_SET_ADDITIONAL_SEARCH_PATH, CMD_CUSTOM_COMMAND, + CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS, //don't go beyond this command! CMD_MAX_CLIENT_COMMANDS, @@ -120,6 +122,8 @@ enum EnumSharedMemoryServerStatus CMD_CALCULATED_INVERSE_DYNAMICS_FAILED, CMD_CALCULATED_JACOBIAN_COMPLETED, CMD_CALCULATED_JACOBIAN_FAILED, + CMD_CALCULATED_MASS_MATRIX_COMPLETED, + CMD_CALCULATED_MASS_MATRIX_FAILED, CMD_CONTACT_POINT_INFORMATION_COMPLETED, CMD_CONTACT_POINT_INFORMATION_FAILED, CMD_REQUEST_AABB_OVERLAP_COMPLETED, @@ -171,7 +175,7 @@ enum EnumSharedMemoryServerStatus CMD_CHANGE_TEXTURE_COMMAND_FAILED, CMD_CUSTOM_COMMAND_COMPLETED, CMD_CUSTOM_COMMAND_FAILED, - + CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS_COMPLETED, //don't go beyond 'CMD_MAX_SERVER_COMMANDS! CMD_MAX_SERVER_COMMANDS }; @@ -214,8 +218,8 @@ enum b3JointInfoFlags struct b3JointInfo { - char* m_linkName; - char* m_jointName; + char m_linkName[1024]; + char m_jointName[1024]; int m_jointType; int m_qIndex; int m_uIndex; @@ -254,8 +258,8 @@ struct b3UserConstraint struct b3BodyInfo { - const char* m_baseName; - const char* m_bodyName; // for btRigidBody, it does not have a base, but can still have a body name from urdf + char m_baseName[1024]; + char m_bodyName[1024]; // for btRigidBody, it does not have a base, but can still have a body name from urdf }; struct b3DynamicsInfo @@ -335,6 +339,7 @@ enum b3VREventType VR_GENERIC_TRACKER_MOVE_EVENT=8, }; +#define MAX_VR_ANALOG_AXIS 5 #define MAX_VR_BUTTONS 64 #define MAX_VR_CONTROLLERS 8 @@ -376,7 +381,7 @@ struct b3VRControllerEvent float m_orn[4];//valid for VR_CONTROLLER_MOVE_EVENT and VR_CONTROLLER_BUTTON_EVENT float m_analogAxis;//valid if VR_CONTROLLER_MOVE_EVENT - + float m_auxAnalogAxis[MAX_VR_ANALOG_AXIS*2];//store x,y per axis, only valid if VR_CONTROLLER_MOVE_EVENT int m_buttons[MAX_VR_BUTTONS];//valid if VR_CONTROLLER_BUTTON_EVENT, see b3VRButtonInfo }; @@ -572,6 +577,7 @@ enum b3ConfigureDebugVisualizerEnum COV_ENABLE_SYNC_RENDERING_INTERNAL, COV_ENABLE_KEYBOARD_SHORTCUTS, COV_ENABLE_MOUSE_PICKING, + COV_ENABLE_Y_AXIS_UP, }; enum b3AddUserDebugItemEnum @@ -633,9 +639,26 @@ struct b3PluginArguments int m_numInts; int m_ints[B3_MAX_PLUGIN_ARG_SIZE]; int m_numFloats; - int m_floats[B3_MAX_PLUGIN_ARG_SIZE]; - + double m_floats[B3_MAX_PLUGIN_ARG_SIZE]; +}; +struct b3PhysicsSimulationParameters +{ + double m_deltaTime; + double m_gravityAcceleration[3]; + int m_numSimulationSubSteps; + int m_numSolverIterations; + int m_useRealTimeSimulation; + int m_useSplitImpulse; + double m_splitImpulsePenetrationThreshold; + double m_contactBreakingThreshold; + int m_internalSimFlags; + double m_defaultContactERP; + int m_collisionFilterMode; + int m_enableFileCaching; + double m_restitutionVelocityThreshold; + double m_defaultNonContactERP; + double m_frictionERP; }; diff --git a/examples/SharedMemory/b3PluginManager.cpp b/examples/SharedMemory/b3PluginManager.cpp index 7f6052349..7ea16c33a 100644 --- a/examples/SharedMemory/b3PluginManager.cpp +++ b/examples/SharedMemory/b3PluginManager.cpp @@ -74,8 +74,11 @@ typedef b3PoolBodyHandle b3PluginHandle; struct b3PluginManagerInternalData { b3ResizablePool m_plugins; - b3HashMap m_pluginMap; + b3HashMap m_pluginMap; PhysicsDirect* m_physicsDirect; + b3AlignedObjectArray m_keyEvents; + b3AlignedObjectArray m_vrEvents; + b3AlignedObjectArray m_mouseEvents; }; b3PluginManager::b3PluginManager(class PhysicsCommandProcessorInterface* physSdk) @@ -89,8 +92,8 @@ b3PluginManager::~b3PluginManager() { while (m_data->m_pluginMap.size()) { - b3PluginHandle* plugin = m_data->m_pluginMap.getAtIndex(0); - unloadPlugin(plugin->m_pluginUniqueId); + b3PluginHandle** plugin = m_data->m_pluginMap.getAtIndex(0); + unloadPlugin((*plugin)->m_pluginUniqueId); } delete m_data->m_physicsDirect; m_data->m_pluginMap.clear(); @@ -98,16 +101,40 @@ b3PluginManager::~b3PluginManager() delete m_data; } +void b3PluginManager::addEvents(const struct b3VRControllerEvent* vrControllerEvents, int numVRControllerEvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents, const struct b3MouseEvent* mouseEvents, int numMouseEvents) +{ -int b3PluginManager::loadPlugin(const char* pluginPath) + for (int i = 0; i < numKeyEvents; i++) + { + m_data->m_keyEvents.push_back(keyEvents[i]); + } + + for (int i = 0; i < numVRControllerEvents; i++) + { + m_data->m_vrEvents.push_back(vrControllerEvents[i]); + } + for (int i = 0; i < numMouseEvents; i++) + { + m_data->m_mouseEvents.push_back(mouseEvents[i]); + } +} + +void b3PluginManager::clearEvents() +{ + m_data->m_keyEvents.resize(0); + m_data->m_vrEvents.resize(0); + m_data->m_mouseEvents.resize(0); +} + +int b3PluginManager::loadPlugin(const char* pluginPath, const char* postFixStr) { int pluginUniqueId = -1; - b3Plugin* pluginOrg = m_data->m_pluginMap.find(pluginPath); - if (pluginOrg) + b3PluginHandle** pluginOrgPtr = m_data->m_pluginMap.find(pluginPath); + if (pluginOrgPtr) { //already loaded - pluginUniqueId = pluginOrg->m_pluginUniqueId; + pluginUniqueId = (*pluginOrgPtr)->m_pluginUniqueId; } else { @@ -118,12 +145,18 @@ int b3PluginManager::loadPlugin(const char* pluginPath) bool ok = false; if (pluginHandle) { + std::string postFix = postFixStr; + std::string initStr = std::string("initPlugin") + postFix; + std::string exitStr = std::string("exitPlugin") + postFix; + std::string executePluginCommandStr = std::string("executePluginCommand") + postFix; + std::string preTickPluginCallbackStr = std::string("preTickPluginCallback") + postFix; + std::string postTickPluginCallback = std::string("postTickPluginCallback") + postFix; - plugin->m_initFunc = (PFN_INIT)B3_DYNLIB_IMPORT(pluginHandle, "initPlugin"); - plugin->m_exitFunc = (PFN_EXIT)B3_DYNLIB_IMPORT(pluginHandle, "exitPlugin"); - plugin->m_executeCommandFunc = (PFN_EXECUTE)B3_DYNLIB_IMPORT(pluginHandle, "executePluginCommand"); - plugin->m_preTickFunc = (PFN_TICK)B3_DYNLIB_IMPORT(pluginHandle, "preTickPluginCallback"); - plugin->m_postTickFunc = (PFN_TICK)B3_DYNLIB_IMPORT(pluginHandle, "postTickPluginCallback"); + plugin->m_initFunc = (PFN_INIT)B3_DYNLIB_IMPORT(pluginHandle, initStr.c_str()); + plugin->m_exitFunc = (PFN_EXIT)B3_DYNLIB_IMPORT(pluginHandle, exitStr.c_str()); + plugin->m_executeCommandFunc = (PFN_EXECUTE)B3_DYNLIB_IMPORT(pluginHandle, executePluginCommandStr.c_str()); + plugin->m_preTickFunc = (PFN_TICK)B3_DYNLIB_IMPORT(pluginHandle, preTickPluginCallbackStr.c_str()); + plugin->m_postTickFunc = (PFN_TICK)B3_DYNLIB_IMPORT(pluginHandle, postTickPluginCallback.c_str()); if (plugin->m_initFunc && plugin->m_exitFunc && plugin->m_executeCommandFunc) { @@ -140,7 +173,7 @@ int b3PluginManager::loadPlugin(const char* pluginPath) plugin->m_ownsPluginHandle = true; plugin->m_pluginHandle = pluginHandle; plugin->m_pluginPath = pluginPath; - m_data->m_pluginMap.insert(pluginPath, *plugin); + m_data->m_pluginMap.insert(pluginPath, plugin); } else { @@ -190,14 +223,28 @@ void b3PluginManager::tickPlugins(double timeStep, bool isPreTick) { for (int i=0;im_pluginMap.size();i++) { - b3PluginHandle* plugin = m_data->m_pluginMap.getAtIndex(i); - + b3PluginHandle** pluginPtr = m_data->m_pluginMap.getAtIndex(i); + b3PluginHandle* plugin = 0; + if (pluginPtr && *pluginPtr) + { + plugin = *pluginPtr; + } + else + { + continue; + } PFN_TICK tick = isPreTick? plugin->m_preTickFunc : plugin->m_postTickFunc; if (tick) { b3PluginContext context; context.m_userPointer = plugin->m_userPointer; context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect; + context.m_numMouseEvents = m_data->m_mouseEvents.size(); + context.m_mouseEvents = m_data->m_mouseEvents.size() ? &m_data->m_mouseEvents[0] : 0; + context.m_numKeyEvents = m_data->m_keyEvents.size(); + context.m_keyEvents = m_data->m_keyEvents.size() ? &m_data->m_keyEvents[0] : 0; + context.m_numVRControllerEvents = m_data->m_vrEvents.size(); + context.m_vrControllerEvents = m_data->m_vrEvents.size()? &m_data->m_vrEvents[0]:0; int result = tick(&context); plugin->m_userPointer = context.m_userPointer; } @@ -214,7 +261,13 @@ int b3PluginManager::executePluginCommand(int pluginUniqueId, const b3PluginArgu b3PluginContext context; context.m_userPointer = plugin->m_userPointer; context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect; - + context.m_numMouseEvents = 0; + context.m_mouseEvents = 0; + context.m_numKeyEvents = 0; + context.m_keyEvents = 0; + context.m_numVRControllerEvents = 0; + context.m_vrControllerEvents = 0; + result = plugin->m_executeCommandFunc(&context, arguments); plugin->m_userPointer = context.m_userPointer; } @@ -242,12 +295,19 @@ int b3PluginManager::registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT pluginHandle->m_pluginPath = pluginPath; pluginHandle->m_userPointer = 0; - m_data->m_pluginMap.insert(pluginPath, *pluginHandle); + m_data->m_pluginMap.insert(pluginPath, pluginHandle); { b3PluginContext context; context.m_userPointer = 0; context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect; + context.m_numMouseEvents = 0; + context.m_mouseEvents = 0; + context.m_numKeyEvents = 0; + context.m_keyEvents = 0; + context.m_numVRControllerEvents = 0; + context.m_vrControllerEvents = 0; + int result = pluginHandle->m_initFunc(&context); pluginHandle->m_userPointer = context.m_userPointer; } diff --git a/examples/SharedMemory/b3PluginManager.h b/examples/SharedMemory/b3PluginManager.h index 6d4fa7ef1..d9466b071 100644 --- a/examples/SharedMemory/b3PluginManager.h +++ b/examples/SharedMemory/b3PluginManager.h @@ -12,10 +12,14 @@ class b3PluginManager b3PluginManager(class PhysicsCommandProcessorInterface* physSdk); virtual ~b3PluginManager(); - int loadPlugin(const char* pluginPath); + int loadPlugin(const char* pluginPath, const char* postFixStr =""); void unloadPlugin(int pluginUniqueId); int executePluginCommand(int pluginUniqueId, const struct b3PluginArguments* arguments); + void addEvents(const struct b3VRControllerEvent* vrControllerEvents, int numVRControllerEvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents, const struct b3MouseEvent* mouseEvents, int numMouseEvents); + void clearEvents(); + void tickPlugins(double timeStep, bool isPreTick); + int registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT initFunc,PFN_EXIT exitFunc, PFN_EXECUTE executeCommandFunc, PFN_TICK preTickFunc, PFN_TICK postTickFunc); }; diff --git a/examples/SharedMemory/plugins/b3PluginContext.h b/examples/SharedMemory/plugins/b3PluginContext.h index cb8bd754d..8d042a3b8 100644 --- a/examples/SharedMemory/plugins/b3PluginContext.h +++ b/examples/SharedMemory/plugins/b3PluginContext.h @@ -5,12 +5,17 @@ struct b3PluginContext { - b3PhysicsClientHandle m_physClient; //plugin can modify the m_userPointer to store persistent object pointer (class or struct instance etc) void* m_userPointer; + const struct b3VRControllerEvent* m_vrControllerEvents; + int m_numVRControllerEvents; + const struct b3KeyboardEvent* m_keyEvents; + int m_numKeyEvents; + const struct b3MouseEvent* m_mouseEvents; + int m_numMouseEvents; }; diff --git a/examples/SharedMemory/plugins/vrSyncPlugin/vrSyncPlugin.cpp b/examples/SharedMemory/plugins/vrSyncPlugin/vrSyncPlugin.cpp index 474e944df..78dc439f1 100644 --- a/examples/SharedMemory/plugins/vrSyncPlugin/vrSyncPlugin.cpp +++ b/examples/SharedMemory/plugins/vrSyncPlugin/vrSyncPlugin.cpp @@ -37,7 +37,7 @@ struct MyClass } }; -B3_SHARED_API int initPlugin(struct b3PluginContext* context) +B3_SHARED_API int initPlugin_vrSyncPlugin(struct b3PluginContext* context) { MyClass* obj = new MyClass(); context->m_userPointer = obj; @@ -47,28 +47,17 @@ B3_SHARED_API int initPlugin(struct b3PluginContext* context) } -B3_SHARED_API int preTickPluginCallback(struct b3PluginContext* context) +B3_SHARED_API int preTickPluginCallback_vrSyncPlugin(struct b3PluginContext* context) { MyClass* obj = (MyClass* )context->m_userPointer; - if (obj->m_controllerId>=0) + if (obj && obj->m_controllerId>=0) { - b3SharedMemoryCommandHandle commandHandle = b3RequestVREventsCommandInit(context->m_physClient); - int deviceTypeFilter = VR_DEVICE_CONTROLLER; - b3VREventsSetDeviceTypeFilter(commandHandle, deviceTypeFilter); - - b3SharedMemoryStatusHandle statusHandle = b3SubmitClientCommandAndWaitStatus(context->m_physClient, commandHandle); - int statusType = b3GetStatusType(statusHandle); - if (statusType == CMD_REQUEST_VR_EVENTS_DATA_COMPLETED) { - struct b3VREventsData vrEvents; - int i = 0; - b3GetVREventsData(context->m_physClient, &vrEvents); - if (vrEvents.m_numControllerEvents) { - for (int n=0;nm_numVRControllerEvents;n++) { - b3VRControllerEvent& event = vrEvents.m_controllerEvents[n]; + const b3VRControllerEvent& event = context->m_vrControllerEvents[n]; if (event.m_controllerId ==obj->m_controllerId) { if (obj->m_constraintId>=0) @@ -171,7 +160,7 @@ B3_SHARED_API int preTickPluginCallback(struct b3PluginContext* context) -B3_SHARED_API int executePluginCommand(struct b3PluginContext* context, const struct b3PluginArguments* arguments) +B3_SHARED_API int executePluginCommand_vrSyncPlugin(struct b3PluginContext* context, const struct b3PluginArguments* arguments) { MyClass* obj = (MyClass*) context->m_userPointer; if (arguments->m_numInts>=4 && arguments->m_numFloats >= 2) @@ -199,7 +188,7 @@ B3_SHARED_API int executePluginCommand(struct b3PluginContext* context, const st } -B3_SHARED_API void exitPlugin(struct b3PluginContext* context) +B3_SHARED_API void exitPlugin_vrSyncPlugin(struct b3PluginContext* context) { MyClass* obj = (MyClass*) context->m_userPointer; delete obj; diff --git a/examples/SharedMemory/plugins/vrSyncPlugin/vrSyncPlugin.h b/examples/SharedMemory/plugins/vrSyncPlugin/vrSyncPlugin.h index fcc60a610..9b4cebd1a 100644 --- a/examples/SharedMemory/plugins/vrSyncPlugin/vrSyncPlugin.h +++ b/examples/SharedMemory/plugins/vrSyncPlugin/vrSyncPlugin.h @@ -9,12 +9,12 @@ extern "C" #endif //initPlugin, exitPlugin and executePluginCommand are required, otherwise plugin won't load -B3_SHARED_API int initPlugin(struct b3PluginContext* context); -B3_SHARED_API void exitPlugin(struct b3PluginContext* context); -B3_SHARED_API int executePluginCommand(struct b3PluginContext* context, const struct b3PluginArguments* arguments); +B3_SHARED_API int initPlugin_vrSyncPlugin(struct b3PluginContext* context); +B3_SHARED_API void exitPlugin_vrSyncPlugin(struct b3PluginContext* context); +B3_SHARED_API int executePluginCommand_vrSyncPlugin(struct b3PluginContext* context, const struct b3PluginArguments* arguments); //preTickPluginCallback and postTickPluginCallback are optional. -B3_SHARED_API int preTickPluginCallback(struct b3PluginContext* context); +B3_SHARED_API int preTickPluginCallback_vrSyncPlugin(struct b3PluginContext* context); diff --git a/examples/StandaloneMain/hellovr_opengl_main.cpp b/examples/StandaloneMain/hellovr_opengl_main.cpp index 1e48f879f..76517c2e6 100644 --- a/examples/StandaloneMain/hellovr_opengl_main.cpp +++ b/examples/StandaloneMain/hellovr_opengl_main.cpp @@ -376,10 +376,16 @@ void MyKeyboardCallback(int key, int state) extern bool useShadowMap; static bool gEnableVRRenderControllers=true; static bool gEnableVRRendering = true; - +static int gUpAxis = 2; void VRPhysicsServerVisualizerFlagCallback(int flag, bool enable) { + if (flag == COV_ENABLE_Y_AXIS_UP) + { + //either Y = up or Z + gUpAxis = enable? 1:2; + } + if (flag == COV_ENABLE_SHADOWS) { useShadowMap = enable; @@ -808,7 +814,15 @@ bool CMainApplication::HandleInput() for (int button = 0; button < vr::k_EButton_Max; button++) { uint64_t trigger = vr::ButtonMaskFromId((vr::EVRButtonId)button); - + + btAssert(vr::k_unControllerStateAxisCount>=5); + float allAxis[10];//store x,y times 5 controllers + int index=0; + for (int i=0;i<5;i++) + { + allAxis[index++]=state.rAxis[i].x; + allAxis[index++]=state.rAxis[i].y; + } bool isTrigger = (state.ulButtonPressed&trigger) != 0; if (isTrigger) { @@ -818,31 +832,15 @@ bool CMainApplication::HandleInput() if ((sPrevStates[unDevice].ulButtonPressed&trigger)==0) { // printf("Device PRESSED: %d, button %d\n", unDevice, button); - if (button==2) - { - //glPolygonMode( GL_FRONT_AND_BACK, GL_LINE ); - - ///todo(erwincoumans) can't use reguar debug drawer, because physics/graphics are not in sync - ///so it can (and likely will) cause crashes - ///add a special debug drawer that deals with this - //gDebugDrawFlags = btIDebugDraw::DBG_DrawWireframe+btIDebugDraw::DBG_DrawContactPoints+ - //btIDebugDraw::DBG_DrawConstraintLimits+ - //btIDebugDraw::DBG_DrawConstraints - //; - //gDebugDrawFlags = btIDebugDraw::DBG_DrawFrames; - - - - } - sExample->vrControllerButtonCallback(unDevice, button, 1, pos, orn); } else { + // printf("Device MOVED: %d\n", unDevice); - sExample->vrControllerMoveCallback(unDevice, pos, orn, state.rAxis[1].x); + sExample->vrControllerMoveCallback(unDevice, pos, orn, state.rAxis[1].x, allAxis); } } else @@ -865,7 +863,7 @@ bool CMainApplication::HandleInput() } else { - sExample->vrControllerMoveCallback(unDevice, pos, orn, state.rAxis[1].x); + sExample->vrControllerMoveCallback(unDevice, pos, orn, state.rAxis[1].x,allAxis); } } } @@ -890,6 +888,7 @@ void CMainApplication::RunMainLoop() while ( !bQuit && !m_app->m_window->requestedExit()) { + this->m_app->setUpAxis(gUpAxis); b3ChromeUtilsEnableProfiling(); if (gEnableVRRendering) { diff --git a/examples/pybullet/examples/vrEvent.py b/examples/pybullet/examples/vrEvent.py index beb369b1d..790d6881b 100644 --- a/examples/pybullet/examples/vrEvent.py +++ b/examples/pybullet/examples/vrEvent.py @@ -8,7 +8,9 @@ import pybullet as p CONTROLLER_ID = 0 POSITION=1 ORIENTATION=2 +NUM_MOVE_EVENTS=5 BUTTONS=6 +ANALOG_AXIS=8 #assume that the VR physics server is already started before c = p.connect(p.SHARED_MEMORY) @@ -20,7 +22,7 @@ p.setInternalSimFlags(0)#don't load default robot assets etc p.resetSimulation() p.loadURDF("plane.urdf") -prevPosition=[None]*p.VR_MAX_CONTROLLERS +prevPosition=[[0,0,0]]*p.VR_MAX_CONTROLLERS colors=[0.,0.5,0.5]*p.VR_MAX_CONTROLLERS widths = [3]*p.VR_MAX_CONTROLLERS @@ -32,10 +34,27 @@ colors[3] = [0,0,0.5] colors[4] = [0.5,0.5,0.] colors[5] = [.5,.5,.5] -while True: +controllerId = -1 +pt=[0,0,0] + +print("waiting for VR controller trigger") +while (controllerId<0): events = p.getVREvents() + for e in (events): + if (e[BUTTONS][33]==p.VR_BUTTON_IS_DOWN): + controllerId = e[CONTROLLER_ID] + if (e[BUTTONS][32]==p.VR_BUTTON_IS_DOWN): + controllerId = e[CONTROLLER_ID] + +print("Using controllerId="+str(controllerId)) + +while True: + events = p.getVREvents(allAnalogAxes=1) for e in (events): + if (e[CONTROLLER_ID]==controllerId ): + for a in range(10): + print("analog axis"+str(a)+"="+str(e[8][a])) if (e[BUTTONS][33]&p.VR_BUTTON_WAS_TRIGGERED): prevPosition[e[CONTROLLER_ID]] = e[POSITION] if (e[BUTTONS][32]&p.VR_BUTTON_WAS_TRIGGERED): @@ -51,7 +70,10 @@ while True: pt = prevPosition[e[CONTROLLER_ID]] #print(prevPosition[e[0]]) - #print(e[1]) + print("e[POSITION]") + print(e[POSITION]) + print("pt") + print(pt) diff = [pt[0]-e[POSITION][0],pt[1]-e[POSITION][1],pt[2]-e[POSITION][2]] lenSqr = diff[0]*diff[0]+diff[1]*diff[1]+diff[2]*diff[2] ptDistThreshold = 0.01 diff --git a/examples/pybullet/examples/vr_kuka_setup_vrSyncPlugin.py b/examples/pybullet/examples/vr_kuka_setup_vrSyncPlugin.py index 7297bdd73..0085e52e4 100644 --- a/examples/pybullet/examples/vr_kuka_setup_vrSyncPlugin.py +++ b/examples/pybullet/examples/vr_kuka_setup_vrSyncPlugin.py @@ -95,8 +95,32 @@ p.setGravity(0,0,-10) p.setRealTimeSimulation(1) -plugin = p.loadPlugin("e:/develop/bullet3/bin/pybullet_vrSyncPlugin_vs2010_x64_release.dll") -controllerId = 3 + + + +CONTROLLER_ID = 0 +POSITION = 1 +ORIENTATION = 2 +BUTTONS = 6 + +controllerId = -1 + +print("waiting for VR controller trigger") +while (controllerId<0): + events = p.getVREvents() + for e in (events): + if (e[BUTTONS][33]==p.VR_BUTTON_IS_DOWN): + controllerId = e[CONTROLLER_ID] + if (e[BUTTONS][32]==p.VR_BUTTON_IS_DOWN): + controllerId = e[CONTROLLER_ID] + +print("Using controllerId="+str(controllerId)) + + +plugin = p.loadPlugin("d:/develop/bullet3/bin/pybullet_vrSyncPlugin_vs2010_x64_release.dll","_vrSyncPlugin") +#plugin = p.loadPlugin("vrSyncPlugin") +print("PluginId="+str(plugin)) + p.executePluginCommand(plugin ,"bla", [controllerId,pr2_cid, pr2_cid2,pr2_gripper],[50,3]) while (1): diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index b332ad650..e2622db3f 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -503,6 +503,35 @@ void b3pybulletExitFunc(void) } +static PyObject* pybullet_getConnectionInfo(PyObject* self, PyObject* args, PyObject* keywds) +{ + int physicsClientId = 0; + int isConnected=0; + int method=0; + PyObject* pylist = 0; + PyObject* val = 0; + b3PhysicsClientHandle sm = 0; + static char* kwlist[] = {"physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist, &physicsClientId)) + { + return NULL; + } + sm = getPhysicsClient(physicsClientId); + if (sm != 0) + { + if (b3CanSubmitCommand(sm)) + { + isConnected = 1; + method = sPhysicsClientsGUI[physicsClientId]; + } + } + + val = Py_BuildValue("{s:i,s:i}","isConnected", isConnected, "connectionMethod", method); + return val; + +} + + static PyObject* pybullet_saveWorld(PyObject* self, PyObject* args, PyObject* keywds) { const char* worldFileName = ""; @@ -824,6 +853,56 @@ static PyObject* pybullet_getDynamicsInfo(PyObject* self, PyObject* args, PyObje return NULL; } +static PyObject* pybullet_getPhysicsEngineParameters(PyObject* self, PyObject* args, PyObject* keywds) +{ + b3PhysicsClientHandle sm = 0; + PyObject* val=0; + int physicsClientId = 0; + static char* kwlist[] = {"physicsClientId", NULL}; + + if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist, &physicsClientId)) + { + return NULL; + } + sm = getPhysicsClient(physicsClientId); + if (sm == 0) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + { + b3SharedMemoryCommandHandle command = b3InitRequestPhysicsParamCommand(sm); + b3SharedMemoryStatusHandle statusHandle; + struct b3PhysicsSimulationParameters params; + int statusType; + + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + statusType = b3GetStatusType(statusHandle); + if (statusType!=CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS_COMPLETED) + { + PyErr_SetString(SpamError, "Couldn't get physics simulation parameters."); + return NULL; + } + b3GetStatusPhysicsSimulationParameters(statusHandle,¶ms); + + //for now, return a subset, expose more/all on request + val = Py_BuildValue("{s:d,s:i,s:i,s:i,s:d,s:d,s:d}", + "fixedTimeStep", params.m_deltaTime, + "numSubSteps", params.m_numSimulationSubSteps, + "numSolverIterations", params.m_numSolverIterations, + "useRealTimeSimulation", params.m_useRealTimeSimulation, + "gravityAccelerationX", params.m_gravityAcceleration[0], + "gravityAccelerationY", params.m_gravityAcceleration[1], + "gravityAccelerationZ", params.m_gravityAcceleration[2] + ); + return val; + } + //"fixedTimeStep", "numSolverIterations", "useSplitImpulse", "splitImpulsePenetrationThreshold", "numSubSteps", "collisionFilterMode", "contactBreakingThreshold", "maxNumCmdPer1ms", "enableFileCaching","restitutionVelocityThreshold", "erp", "contactERP", "frictionERP", + //val = Py_BuildValue("{s:i,s:i}","isConnected", isConnected, "connectionMethod", method); + + +} static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* args, PyObject* keywds) { @@ -918,19 +997,10 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar { b3PhysicsParamSetDefaultFrictionERP(command,frictionERP); } - //ret = b3PhysicsParamSetRealTimeSimulation(command, enableRealTimeSimulation); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); } -#if 0 - b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient); - int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, double gravx, double gravy, double gravz); - int b3PhysicsParamSetTimeStep(b3SharedMemoryCommandHandle commandHandle, double timeStep); - int b3PhysicsParamSetDefaultContactERP(b3SharedMemoryCommandHandle commandHandle, double defaultContactERP); - int b3PhysicsParamSetNumSubSteps(b3SharedMemoryCommandHandle commandHandle, int numSubSteps); - int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandHandle commandHandle, int enableRealTimeSimulation); - int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHandle, int numSolverIterations); -#endif + Py_INCREF(Py_None); return Py_None; @@ -4207,9 +4277,10 @@ static PyObject* pybullet_getVREvents(PyObject* self, PyObject* args, PyObject* int statusType; int deviceTypeFilter = VR_DEVICE_CONTROLLER; int physicsClientId = 0; + int allAnalogAxes = 0; b3PhysicsClientHandle sm = 0; - static char* kwlist[] = {"deviceTypeFilter", "physicsClientId", NULL}; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "|ii", kwlist, &deviceTypeFilter, &physicsClientId)) + static char* kwlist[] = {"deviceTypeFilter", "allAnalogAxes", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "|iii", kwlist, &deviceTypeFilter, &allAnalogAxes, &physicsClientId)) { return NULL; } @@ -4237,7 +4308,8 @@ static PyObject* pybullet_getVREvents(PyObject* self, PyObject* args, PyObject* vrEventsObj = PyTuple_New(vrEvents.m_numControllerEvents); for (i = 0; i < vrEvents.m_numControllerEvents; i++) { - PyObject* vrEventObj = PyTuple_New(8); + int numFields = allAnalogAxes? 9 : 8; + PyObject* vrEventObj = PyTuple_New(numFields); PyTuple_SetItem(vrEventObj, 0, PyInt_FromLong(vrEvents.m_controllerEvents[i].m_controllerId)); { @@ -4270,6 +4342,19 @@ static PyObject* pybullet_getVREvents(PyObject* self, PyObject* args, PyObject* PyTuple_SetItem(vrEventObj, 6, buttonsObj); } PyTuple_SetItem(vrEventObj, 7, PyInt_FromLong(vrEvents.m_controllerEvents[i].m_deviceType)); + + if (allAnalogAxes) + { + PyObject* buttonsObj = PyTuple_New(MAX_VR_ANALOG_AXIS*2); + int b; + for (b = 0; b < MAX_VR_ANALOG_AXIS*2; b++) + { + PyObject* axisVal = PyFloat_FromDouble(vrEvents.m_controllerEvents[i].m_auxAnalogAxis[b]); + PyTuple_SetItem(buttonsObj, b, axisVal); + } + PyTuple_SetItem(vrEventObj, 8, buttonsObj); + } + PyTuple_SetItem(vrEventsObj, i, vrEventObj); } return vrEventsObj; @@ -6681,13 +6766,15 @@ static PyObject* pybullet_loadPlugin(PyObject* self, int physicsClientId = 0; char* pluginPath = 0; + char* postFix = 0; + b3SharedMemoryCommandHandle command = 0; b3SharedMemoryStatusHandle statusHandle = 0; int statusType = -1; b3PhysicsClientHandle sm = 0; - static char* kwlist[] = { "pluginPath", "physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|i", kwlist, &pluginPath, &physicsClientId)) + static char* kwlist[] = { "pluginPath", "postFix", "physicsClientId", NULL }; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|si", kwlist, &pluginPath, &postFix, &physicsClientId)) { return NULL; } @@ -6701,6 +6788,10 @@ static PyObject* pybullet_loadPlugin(PyObject* self, command = b3CreateCustomCommand(sm); b3CustomCommandLoadPlugin(command, pluginPath); + if (postFix) + { + b3CustomCommandLoadPluginSetPostFix(command, postFix); + } statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusType = b3GetStatusPluginUniqueId(statusHandle); return PyInt_FromLong(statusType); @@ -7162,8 +7253,8 @@ static PyObject* pybullet_calculateJacobian(PyObject* self, PyObject* args, PyOb double* jointPositions = (double*)malloc(byteSizeJoints); double* jointVelocities = (double*)malloc(byteSizeJoints); double* jointAccelerations = (double*)malloc(byteSizeJoints); - double* linearJacobian = (double*)malloc(3 * byteSizeJoints); - double* angularJacobian = (double*)malloc(3 * byteSizeJoints); + double* linearJacobian = NULL; + double* angularJacobian = NULL; pybullet_internalSetVectord(localPosition, localPoint); for (i = 0; i < numJoints; i++) @@ -7261,6 +7352,101 @@ static PyObject* pybullet_calculateJacobian(PyObject* self, PyObject* args, PyOb return Py_None; } +/// Given an object id, joint positions, joint velocities and joint +/// accelerations, compute the Jacobian +static PyObject* pybullet_calculateMassMatrix(PyObject* self, PyObject* args, PyObject* keywds) +{ + { + int bodyUniqueId; + PyObject* objPositions; + int physicsClientId = 0; + b3PhysicsClientHandle sm = 0; + static char* kwlist[] = {"bodyUniqueId", "objPositions", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "iO|i", kwlist, + &bodyUniqueId, &objPositions, &physicsClientId)) + { + return NULL; + } + sm = getPhysicsClient(physicsClientId); + if (sm == 0) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + { + int szObPos = PySequence_Size(objPositions); + int numJoints = b3GetNumJoints(sm, bodyUniqueId); + if (numJoints && (szObPos == numJoints)) + { + int byteSizeJoints = sizeof(double) * numJoints; + PyObject* pyResultList; + double* jointPositions = (double*)malloc(byteSizeJoints); + double* massMatrix = NULL; + int i; + for (i = 0; i < numJoints; i++) + { + jointPositions[i] = + pybullet_internalGetFloatFromSequence(objPositions, i); + } + { + b3SharedMemoryStatusHandle statusHandle; + int statusType; + b3SharedMemoryCommandHandle commandHandle = + b3CalculateMassMatrixCommandInit(sm, bodyUniqueId, jointPositions); + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + statusType = b3GetStatusType(statusHandle); + if (statusType == CMD_CALCULATED_MASS_MATRIX_COMPLETED) + { + int dofCount; + b3GetStatusMassMatrix(sm, statusHandle, &dofCount, NULL); + if (dofCount) + { + int byteSizeDofCount = sizeof(double) * dofCount; + pyResultList = PyTuple_New(dofCount); + + massMatrix = (double*)malloc(dofCount * byteSizeDofCount); + b3GetStatusMassMatrix(sm, statusHandle, NULL, massMatrix); + if (massMatrix) + { + int r; + for (r = 0; r < dofCount; ++r) { + int c; + PyObject* pyrow = PyTuple_New(dofCount); + for (c = 0; c < dofCount; ++c) { + int element = r * dofCount + c; + PyTuple_SetItem(pyrow, c, + PyFloat_FromDouble(massMatrix[element])); + } + PyTuple_SetItem(pyResultList, r, pyrow); + } + } + } + } + else + { + PyErr_SetString(SpamError, + "Internal error in calculateJacobian"); + } + } + free(jointPositions); + free(massMatrix); + if (pyResultList) return pyResultList; + } + else + { + PyErr_SetString(SpamError, + "calculateMassMatrix [numJoints] needs to be " + "positive and [joint positions] " + "need to match the number of joints."); + return NULL; + } + } + } + Py_INCREF(Py_None); + return Py_None; +} + static PyMethodDef SpamMethods[] = { {"connect", (PyCFunction)pybullet_connectPhysicsServer, METH_VARARGS | METH_KEYWORDS, @@ -7272,6 +7458,10 @@ static PyMethodDef SpamMethods[] = { "disconnect(physicsClientId=0)\n" "Disconnect from the physics server."}, + {"getConnectionInfo", (PyCFunction)pybullet_getConnectionInfo, METH_VARARGS | METH_KEYWORDS, + "getConnectionInfo(physicsClientId=0)\n" + "Return if a given client id is connected, and using what method."}, + {"resetSimulation", (PyCFunction)pybullet_resetSimulation, METH_VARARGS | METH_KEYWORDS, "resetSimulation(physicsClientId=0)\n" "Reset the simulation: remove all objects and start from an empty world."}, @@ -7304,6 +7494,9 @@ static PyMethodDef SpamMethods[] = { {"setPhysicsEngineParameter", (PyCFunction)pybullet_setPhysicsEngineParameter, METH_VARARGS | METH_KEYWORDS, "Set some internal physics engine parameter, such as cfm or erp etc."}, + {"getPhysicsEngineParameters", (PyCFunction)pybullet_getPhysicsEngineParameters, METH_VARARGS | METH_KEYWORDS, + "Get the current values of internal physics engine parameters"}, + {"setInternalSimFlags", (PyCFunction)pybullet_setInternalSimFlags, METH_VARARGS | METH_KEYWORDS, "This is for experimental purposes, use at own risk, magic may or not happen"}, @@ -7566,6 +7759,8 @@ static PyMethodDef SpamMethods[] = { "accelerations, compute the joint forces using Inverse Dynamics"}, {"calculateJacobian", (PyCFunction)pybullet_calculateJacobian, METH_VARARGS | METH_KEYWORDS, + "linearJacobian, angularJacobian = calculateJacobian(bodyUniqueId, " + "linkIndex, localPosition, objPositions, objVelocities, objAccelerations, physicsClientId=0)\n" "Compute the jacobian for a specified local position on a body and its kinematics.\n" "Args:\n" " bodyIndex - a scalar defining the unique object id.\n" @@ -7577,6 +7772,15 @@ static PyMethodDef SpamMethods[] = { "Returns:\n" " linearJacobian - a list of the partial linear velocities of the jacobian.\n" " angularJacobian - a list of the partial angular velocities of the jacobian.\n"}, + + {"calculateMassMatrix", (PyCFunction)pybullet_calculateMassMatrix, METH_VARARGS | METH_KEYWORDS, + "massMatrix = calculateMassMatrix(bodyUniqueId, objPositions, physicsClientId=0)\n" + "Compute the mass matrix for an object and its chain of bodies.\n" + "Args:\n" + " bodyIndex - a scalar defining the unique object id.\n" + " objPositions - a list of the joint positions.\n" + "Returns:\n" + " massMatrix - a list of lists of the mass matrix components.\n"}, {"calculateInverseKinematics", (PyCFunction)pybullet_calculateInverseKinematics, METH_VARARGS | METH_KEYWORDS, diff --git a/examples/pybullet/unity3d/autogen/NativeMethods.cs b/examples/pybullet/unity3d/autogen/NativeMethods.cs index 29ec9f4f0..ec5e1543f 100644 --- a/examples/pybullet/unity3d/autogen/NativeMethods.cs +++ b/examples/pybullet/unity3d/autogen/NativeMethods.cs @@ -425,13 +425,13 @@ public enum b3JointInfoFlags { [System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] public struct b3JointInfo { - - /// char* - [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] + + /// char[1024] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValTStr, SizeConst = 1024)] public string m_linkName; - - /// char* - [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] + + /// char[1024] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValTStr, SizeConst = 1024)] public string m_jointName; /// int @@ -531,13 +531,13 @@ public struct b3UserConstraint { [System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] public struct b3BodyInfo { - - /// char* - [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] + + /// char[1024] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValTStr, SizeConst = 1024)] public string m_baseName; - - /// char* - [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] + + /// char[1024] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValTStr, SizeConst = 1024)] public string m_bodyName; } @@ -624,8 +624,7 @@ public struct b3CameraImageData { public int m_pixelHeight; /// char* - [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] - public string m_rgbColorData; + public System.IntPtr m_rgbColorData; /// float* public System.IntPtr m_depthValues; @@ -1195,68 +1194,70 @@ public struct b3SharedMemoryStatusHandle__ { } public partial class NativeMethods { - + + const string dllName = "pybullet_vs2010_x64_release.dll"; + /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///key: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ConnectSharedMemory")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ConnectSharedMemory")] public static extern System.IntPtr b3ConnectSharedMemory(int key) ; /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///key: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ConnectSharedMemory2")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ConnectSharedMemory2")] public static extern System.IntPtr b3ConnectSharedMemory2(int key) ; /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ConnectPhysicsDirect")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ConnectPhysicsDirect")] public static extern System.IntPtr b3ConnectPhysicsDirect() ; /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///argc: int ///argv: char** - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateInProcessPhysicsServerAndConnect")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, 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("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateInProcessPhysicsServerAndConnectSharedMemory")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, 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("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateInProcessPhysicsServerAndConnectMainThread")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, 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("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateInProcessPhysicsServerAndConnectMainThreadSharedMemory")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateInProcessPhysicsServerAndConnectMainThreadSharedMemory")] public static extern System.IntPtr b3CreateInProcessPhysicsServerAndConnectMainThreadSharedMemory(int argc, ref System.IntPtr argv) ; /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///guiHelperPtr: void* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect")] public static extern System.IntPtr b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect(System.IntPtr guiHelperPtr) ; /// Return Type: void ///clientHandle: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InProcessRenderSceneInternal")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InProcessRenderSceneInternal")] public static extern void b3InProcessRenderSceneInternal(IntPtr clientHandle) ; /// Return Type: void ///clientHandle: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///debugDrawMode: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InProcessDebugDrawInternal")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InProcessDebugDrawInternal")] public static extern void b3InProcessDebugDrawInternal(IntPtr clientHandle, int debugDrawMode) ; @@ -1264,7 +1265,7 @@ public static extern void b3InProcessDebugDrawInternal(IntPtr clientHandle, int ///clientHandle: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///x: float ///y: float - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InProcessMouseMoveCallback")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InProcessMouseMoveCallback")] public static extern int b3InProcessMouseMoveCallback(IntPtr clientHandle, float x, float y) ; @@ -1274,77 +1275,77 @@ public static extern int b3InProcessMouseMoveCallback(IntPtr clientHandle, floa ///state: int ///x: float ///y: float - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InProcessMouseButtonCallback")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InProcessMouseButtonCallback")] public static extern int b3InProcessMouseButtonCallback(IntPtr clientHandle, int button, int state, float x, float y) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3DisconnectSharedMemory")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3DisconnectSharedMemory")] public static extern void b3DisconnectSharedMemory(IntPtr physClient) ; /// Return Type: int ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CanSubmitCommand")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CanSubmitCommand")] public static extern int b3CanSubmitCommand(IntPtr physClient) ; /// Return Type: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SubmitClientCommandAndWaitStatus")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3SubmitClientCommandAndWaitStatus")] public static extern System.IntPtr b3SubmitClientCommandAndWaitStatus(IntPtr physClient, IntPtr commandHandle) ; /// Return Type: int ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SubmitClientCommand")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3SubmitClientCommand")] public static extern int b3SubmitClientCommand(IntPtr physClient, IntPtr commandHandle) ; /// Return Type: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ProcessServerStatus")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ProcessServerStatus")] public static extern System.IntPtr b3ProcessServerStatus(IntPtr physClient) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusType")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetStatusType")] public static extern int b3GetStatusType(IntPtr statusHandle) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateCustomCommand")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateCustomCommand")] public static extern System.IntPtr b3CreateCustomCommand(IntPtr physClient) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///pluginPath: char* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CustomCommandLoadPlugin")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CustomCommandLoadPlugin")] public static extern void b3CustomCommandLoadPlugin(IntPtr commandHandle, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string pluginPath) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusPluginUniqueId")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetStatusPluginUniqueId")] public static extern int b3GetStatusPluginUniqueId(IntPtr statusHandle) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusPluginCommandResult")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetStatusPluginCommandResult")] public static extern int b3GetStatusPluginCommandResult(IntPtr statusHandle) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///pluginUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CustomCommandUnloadPlugin")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CustomCommandUnloadPlugin")] public static extern void b3CustomCommandUnloadPlugin(IntPtr commandHandle, int pluginUniqueId) ; @@ -1352,21 +1353,21 @@ public static extern void b3CustomCommandUnloadPlugin(IntPtr commandHandle, int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///pluginUniqueId: int ///textArguments: char* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CustomCommandExecutePluginCommand")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CustomCommandExecutePluginCommand")] public static extern void b3CustomCommandExecutePluginCommand(IntPtr commandHandle, int pluginUniqueId, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string textArguments) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///intVal: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CustomCommandExecuteAddIntArgument")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CustomCommandExecuteAddIntArgument")] public static extern void b3CustomCommandExecuteAddIntArgument(IntPtr commandHandle, int intVal) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///floatVal: float - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CustomCommandExecuteAddFloatArgument")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CustomCommandExecuteAddFloatArgument")] public static extern void b3CustomCommandExecuteAddFloatArgument(IntPtr commandHandle, float floatVal) ; @@ -1374,13 +1375,13 @@ public static extern void b3CustomCommandExecuteAddFloatArgument(IntPtr command ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* ///bodyIndicesOut: int* ///bodyIndicesCapacity: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusBodyIndices")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetStatusBodyIndices")] public static extern int b3GetStatusBodyIndices(IntPtr statusHandle, ref int bodyIndicesOut, int bodyIndicesCapacity) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusBodyIndex")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetStatusBodyIndex")] public static extern int b3GetStatusBodyIndex(IntPtr statusHandle) ; @@ -1393,14 +1394,14 @@ public static extern int b3GetStatusBodyIndex(IntPtr statusHandle) ; ///actualStateQ: double** ///actualStateQdot: double** ///jointReactionForces: double** - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusActualState")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetStatusActualState")] public static extern int b3GetStatusActualState(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("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCollisionInfoCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3RequestCollisionInfoCommandInit")] public static extern System.IntPtr b3RequestCollisionInfoCommandInit(IntPtr physClient, int bodyUniqueId) ; @@ -1409,33 +1410,33 @@ public static extern System.IntPtr b3RequestCollisionInfoCommandInit(IntPtr phy ///linkIndex: int ///aabbMin: double* ///aabbMax: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusAABB")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetStatusAABB")] public static extern int b3GetStatusAABB(IntPtr statusHandle, int linkIndex, ref double aabbMin, ref double aabbMax) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitSyncBodyInfoCommand")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitSyncBodyInfoCommand")] public static extern System.IntPtr b3InitSyncBodyInfoCommand(IntPtr physClient) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitRemoveBodyCommand")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitRemoveBodyCommand")] public static extern System.IntPtr b3InitRemoveBodyCommand(IntPtr physClient, int bodyUniqueId) ; /// Return Type: int ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetNumBodies")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetNumBodies")] public static extern int b3GetNumBodies(IntPtr physClient) ; /// Return Type: int ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///serialIndex: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetBodyUniqueId")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetBodyUniqueId")] public static extern int b3GetBodyUniqueId(IntPtr physClient, int serialIndex) ; @@ -1443,14 +1444,14 @@ public static extern int b3GetBodyUniqueId(IntPtr physClient, int serialIndex) ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyUniqueId: int ///info: b3BodyInfo* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetBodyInfo")] -public static extern int b3GetBodyInfo(IntPtr physClient, int bodyUniqueId, ref b3BodyInfo info) ; + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetBodyInfo")] + public static extern int b3GetBodyInfo(IntPtr physClient, int bodyUniqueId, ref b3BodyInfo info) ; /// Return Type: int ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetNumJoints")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetNumJoints")] public static extern int b3GetNumJoints(IntPtr physClient, int bodyId) ; @@ -1459,7 +1460,7 @@ public static extern int b3GetNumJoints(IntPtr physClient, int bodyId) ; ///bodyIndex: int ///jointIndex: int ///info: b3JointInfo* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetJointInfo")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetJointInfo")] public static extern int b3GetJointInfo(IntPtr physClient, int bodyIndex, int jointIndex, ref b3JointInfo info) ; @@ -1467,20 +1468,20 @@ public static extern int b3GetJointInfo(IntPtr physClient, int bodyIndex, int j ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyUniqueId: int ///linkIndex: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetDynamicsInfoCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetDynamicsInfoCommandInit")] public static extern System.IntPtr b3GetDynamicsInfoCommandInit(IntPtr physClient, int bodyUniqueId, int linkIndex) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* ///info: b3DynamicsInfo* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetDynamicsInfo")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetDynamicsInfo")] public static extern int b3GetDynamicsInfo(IntPtr statusHandle, ref b3DynamicsInfo info) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitChangeDynamicsInfo")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitChangeDynamicsInfo")] public static extern System.IntPtr b3InitChangeDynamicsInfo(IntPtr physClient) ; @@ -1489,7 +1490,7 @@ public static extern System.IntPtr b3InitChangeDynamicsInfo(IntPtr physClient) ///bodyUniqueId: int ///linkIndex: int ///mass: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ChangeDynamicsInfoSetMass")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ChangeDynamicsInfoSetMass")] public static extern int b3ChangeDynamicsInfoSetMass(IntPtr commandHandle, int bodyUniqueId, int linkIndex, double mass) ; @@ -1498,7 +1499,7 @@ public static extern int b3ChangeDynamicsInfoSetMass(IntPtr commandHandle, int ///bodyUniqueId: int ///linkIndex: int ///lateralFriction: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ChangeDynamicsInfoSetLateralFriction")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ChangeDynamicsInfoSetLateralFriction")] public static extern int b3ChangeDynamicsInfoSetLateralFriction(IntPtr commandHandle, int bodyUniqueId, int linkIndex, double lateralFriction) ; @@ -1507,7 +1508,7 @@ public static extern int b3ChangeDynamicsInfoSetLateralFriction(IntPtr commandH ///bodyUniqueId: int ///linkIndex: int ///friction: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ChangeDynamicsInfoSetSpinningFriction")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ChangeDynamicsInfoSetSpinningFriction")] public static extern int b3ChangeDynamicsInfoSetSpinningFriction(IntPtr commandHandle, int bodyUniqueId, int linkIndex, double friction) ; @@ -1516,7 +1517,7 @@ public static extern int b3ChangeDynamicsInfoSetSpinningFriction(IntPtr command ///bodyUniqueId: int ///linkIndex: int ///friction: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ChangeDynamicsInfoSetRollingFriction")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ChangeDynamicsInfoSetRollingFriction")] public static extern int b3ChangeDynamicsInfoSetRollingFriction(IntPtr commandHandle, int bodyUniqueId, int linkIndex, double friction) ; @@ -1525,7 +1526,7 @@ public static extern int b3ChangeDynamicsInfoSetRollingFriction(IntPtr commandH ///bodyUniqueId: int ///linkIndex: int ///restitution: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ChangeDynamicsInfoSetRestitution")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ChangeDynamicsInfoSetRestitution")] public static extern int b3ChangeDynamicsInfoSetRestitution(IntPtr commandHandle, int bodyUniqueId, int linkIndex, double restitution) ; @@ -1533,7 +1534,7 @@ public static extern int b3ChangeDynamicsInfoSetRestitution(IntPtr commandHandl ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///bodyUniqueId: int ///linearDamping: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ChangeDynamicsInfoSetLinearDamping")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ChangeDynamicsInfoSetLinearDamping")] public static extern int b3ChangeDynamicsInfoSetLinearDamping(IntPtr commandHandle, int bodyUniqueId, double linearDamping) ; @@ -1541,7 +1542,7 @@ public static extern int b3ChangeDynamicsInfoSetLinearDamping(IntPtr commandHan ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///bodyUniqueId: int ///angularDamping: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ChangeDynamicsInfoSetAngularDamping")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ChangeDynamicsInfoSetAngularDamping")] public static extern int b3ChangeDynamicsInfoSetAngularDamping(IntPtr commandHandle, int bodyUniqueId, double angularDamping) ; @@ -1551,7 +1552,7 @@ public static extern int b3ChangeDynamicsInfoSetAngularDamping(IntPtr commandHa ///linkIndex: int ///contactStiffness: double ///contactDamping: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ChangeDynamicsInfoSetContactStiffnessAndDamping")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ChangeDynamicsInfoSetContactStiffnessAndDamping")] public static extern int b3ChangeDynamicsInfoSetContactStiffnessAndDamping(IntPtr commandHandle, int bodyUniqueId, int linkIndex, double contactStiffness, double contactDamping) ; @@ -1560,7 +1561,7 @@ public static extern int b3ChangeDynamicsInfoSetContactStiffnessAndDamping(IntP ///bodyUniqueId: int ///linkIndex: int ///frictionAnchor: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ChangeDynamicsInfoSetFrictionAnchor")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ChangeDynamicsInfoSetFrictionAnchor")] public static extern int b3ChangeDynamicsInfoSetFrictionAnchor(IntPtr commandHandle, int bodyUniqueId, int linkIndex, int frictionAnchor) ; @@ -1571,82 +1572,82 @@ public static extern int b3ChangeDynamicsInfoSetFrictionAnchor(IntPtr commandHa ///childBodyIndex: int ///childJointIndex: int ///info: b3JointInfo* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitCreateUserConstraintCommand")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitCreateUserConstraintCommand")] public static extern System.IntPtr b3InitCreateUserConstraintCommand(IntPtr physClient, int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, ref b3JointInfo info) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusUserConstraintUniqueId")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetStatusUserConstraintUniqueId")] public static extern int b3GetStatusUserConstraintUniqueId(IntPtr statusHandle) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///userConstraintUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitChangeUserConstraintCommand")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitChangeUserConstraintCommand")] public static extern System.IntPtr b3InitChangeUserConstraintCommand(IntPtr physClient, int userConstraintUniqueId) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///jointChildPivot: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitChangeUserConstraintSetPivotInB")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitChangeUserConstraintSetPivotInB")] public static extern int b3InitChangeUserConstraintSetPivotInB(IntPtr commandHandle, ref double jointChildPivot) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///jointChildFrameOrn: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitChangeUserConstraintSetFrameInB")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitChangeUserConstraintSetFrameInB")] public static extern int b3InitChangeUserConstraintSetFrameInB(IntPtr commandHandle, ref double jointChildFrameOrn) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///maxAppliedForce: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitChangeUserConstraintSetMaxForce")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitChangeUserConstraintSetMaxForce")] public static extern int b3InitChangeUserConstraintSetMaxForce(IntPtr commandHandle, double maxAppliedForce) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///gearRatio: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitChangeUserConstraintSetGearRatio")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitChangeUserConstraintSetGearRatio")] public static extern int b3InitChangeUserConstraintSetGearRatio(IntPtr commandHandle, double gearRatio) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///gearAuxLink: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitChangeUserConstraintSetGearAuxLink")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitChangeUserConstraintSetGearAuxLink")] public static extern int b3InitChangeUserConstraintSetGearAuxLink(IntPtr commandHandle, int gearAuxLink) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///relativePositionTarget: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitChangeUserConstraintSetRelativePositionTarget")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitChangeUserConstraintSetRelativePositionTarget")] public static extern int b3InitChangeUserConstraintSetRelativePositionTarget(IntPtr commandHandle, double relativePositionTarget) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///erp: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitChangeUserConstraintSetERP")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitChangeUserConstraintSetERP")] public static extern int b3InitChangeUserConstraintSetERP(IntPtr commandHandle, double erp) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///userConstraintUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitRemoveUserConstraintCommand")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitRemoveUserConstraintCommand")] public static extern System.IntPtr b3InitRemoveUserConstraintCommand(IntPtr physClient, int userConstraintUniqueId) ; /// Return Type: int ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetNumUserConstraints")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetNumUserConstraints")] public static extern int b3GetNumUserConstraints(IntPtr physClient) ; @@ -1654,34 +1655,34 @@ public static extern int b3GetNumUserConstraints(IntPtr physClient) ; ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///constraintUniqueId: int ///info: b3UserConstraint* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetUserConstraintInfo")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetUserConstraintInfo")] public static extern int b3GetUserConstraintInfo(IntPtr physClient, int constraintUniqueId, ref b3UserConstraint info) ; /// Return Type: int ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///serialIndex: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetUserConstraintId")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetUserConstraintId")] public static extern int b3GetUserConstraintId(IntPtr physClient, int serialIndex) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///debugMode: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitRequestDebugLinesCommand")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitRequestDebugLinesCommand")] public static extern System.IntPtr b3InitRequestDebugLinesCommand(IntPtr physClient, int debugMode) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///lines: b3DebugLines* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetDebugLines")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetDebugLines")] public static extern void b3GetDebugLines(IntPtr physClient, ref b3DebugLines lines) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitConfigureOpenGLVisualizer")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitConfigureOpenGLVisualizer")] public static extern System.IntPtr b3InitConfigureOpenGLVisualizer(IntPtr physClient) ; @@ -1689,7 +1690,7 @@ public static extern System.IntPtr b3InitConfigureOpenGLVisualizer(IntPtr physC ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///flag: int ///enabled: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ConfigureOpenGLVisualizerSetVisualizationFlags")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ConfigureOpenGLVisualizerSetVisualizationFlags")] public static extern void b3ConfigureOpenGLVisualizerSetVisualizationFlags(IntPtr commandHandle, int flag, int enabled) ; @@ -1699,20 +1700,20 @@ public static extern void b3ConfigureOpenGLVisualizerSetVisualizationFlags(IntP ///cameraPitch: float ///cameraYaw: float ///cameraTargetPosition: float* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ConfigureOpenGLVisualizerSetViewMatrix")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ConfigureOpenGLVisualizerSetViewMatrix")] public static extern void b3ConfigureOpenGLVisualizerSetViewMatrix(IntPtr commandHandle, float cameraDistance, float cameraPitch, float cameraYaw, ref float cameraTargetPosition) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitRequestOpenGLVisualizerCameraCommand")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitRequestOpenGLVisualizerCameraCommand")] public static extern System.IntPtr b3InitRequestOpenGLVisualizerCameraCommand(IntPtr physClient) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* ///camera: b3OpenGLVisualizerCameraInfo* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusOpenGLVisualizerCamera")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetStatusOpenGLVisualizerCamera")] public static extern int b3GetStatusOpenGLVisualizerCamera(IntPtr statusHandle, ref b3OpenGLVisualizerCameraInfo camera) ; @@ -1723,7 +1724,7 @@ public static extern int b3GetStatusOpenGLVisualizerCamera(IntPtr statusHandle, ///colorRGB: double* ///lineWidth: double ///lifeTime: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitUserDebugDrawAddLine3D")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitUserDebugDrawAddLine3D")] public static extern System.IntPtr b3InitUserDebugDrawAddLine3D(IntPtr physClient, ref double fromXYZ, ref double toXYZ, ref double colorRGB, double lineWidth, double lifeTime) ; @@ -1734,21 +1735,21 @@ public static extern System.IntPtr b3InitUserDebugDrawAddLine3D(IntPtr physClie ///colorRGB: double* ///textSize: double ///lifeTime: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitUserDebugDrawAddText3D")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitUserDebugDrawAddText3D")] public static extern System.IntPtr b3InitUserDebugDrawAddText3D(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("pybullet_vs2010_x64_release.dll", EntryPoint="b3UserDebugTextSetOptionFlags")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3UserDebugTextSetOptionFlags")] public static extern void b3UserDebugTextSetOptionFlags(IntPtr commandHandle, int optionFlags) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///orientation: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3UserDebugTextSetOrientation")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3UserDebugTextSetOrientation")] public static extern void b3UserDebugTextSetOrientation(IntPtr commandHandle, ref double orientation) ; @@ -1756,7 +1757,7 @@ public static extern void b3UserDebugTextSetOrientation(IntPtr commandHandle, r ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///objectUniqueId: int ///linkIndex: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3UserDebugItemSetParentObject")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3UserDebugItemSetParentObject")] public static extern void b3UserDebugItemSetParentObject(IntPtr commandHandle, int objectUniqueId, int linkIndex) ; @@ -1766,40 +1767,40 @@ public static extern void b3UserDebugItemSetParentObject(IntPtr commandHandle, ///rangeMin: double ///rangeMax: double ///startValue: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitUserDebugAddParameter")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitUserDebugAddParameter")] public static extern System.IntPtr b3InitUserDebugAddParameter(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("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitUserDebugReadParameter")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitUserDebugReadParameter")] public static extern System.IntPtr b3InitUserDebugReadParameter(IntPtr physClient, int debugItemUniqueId) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* ///paramValue: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusDebugParameterValue")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetStatusDebugParameterValue")] public static extern int b3GetStatusDebugParameterValue(IntPtr statusHandle, ref double paramValue) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///debugItemUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitUserDebugDrawRemove")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitUserDebugDrawRemove")] public static extern System.IntPtr b3InitUserDebugDrawRemove(IntPtr physClient, int debugItemUniqueId) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitUserDebugDrawRemoveAll")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitUserDebugDrawRemoveAll")] public static extern System.IntPtr b3InitUserDebugDrawRemoveAll(IntPtr physClient) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitDebugDrawingCommand")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitDebugDrawingCommand")] public static extern System.IntPtr b3InitDebugDrawingCommand(IntPtr physClient) ; @@ -1808,7 +1809,7 @@ public static extern System.IntPtr b3InitDebugDrawingCommand(IntPtr physClient) ///objectUniqueId: int ///linkIndex: int ///objectColorRGB: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetDebugObjectColor")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3SetDebugObjectColor")] public static extern void b3SetDebugObjectColor(IntPtr commandHandle, int objectUniqueId, int linkIndex, ref double objectColorRGB) ; @@ -1816,19 +1817,19 @@ public static extern void b3SetDebugObjectColor(IntPtr commandHandle, int objec ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///objectUniqueId: int ///linkIndex: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RemoveDebugObjectColor")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3RemoveDebugObjectColor")] public static extern void b3RemoveDebugObjectColor(IntPtr commandHandle, int objectUniqueId, int linkIndex) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetDebugItemUniqueId")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetDebugItemUniqueId")] public static extern int b3GetDebugItemUniqueId(IntPtr statusHandle) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitRequestCameraImage")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitRequestCameraImage")] public static extern System.IntPtr b3InitRequestCameraImage(IntPtr physClient) ; @@ -1836,7 +1837,7 @@ public static extern System.IntPtr b3InitRequestCameraImage(IntPtr physClient) ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///viewMatrix: float* ///projectionMatrix: float* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetCameraMatrices")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3RequestCameraImageSetCameraMatrices")] public static extern void b3RequestCameraImageSetCameraMatrices(IntPtr commandHandle, ref float viewMatrix, ref float projectionMatrix) ; @@ -1844,70 +1845,70 @@ public static extern void b3RequestCameraImageSetCameraMatrices(IntPtr commandH ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///width: int ///height: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetPixelResolution")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3RequestCameraImageSetPixelResolution")] public static extern void b3RequestCameraImageSetPixelResolution(IntPtr commandHandle, int width, int height) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///lightDirection: float* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetLightDirection")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3RequestCameraImageSetLightDirection")] public static extern void b3RequestCameraImageSetLightDirection(IntPtr commandHandle, ref float lightDirection) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///lightColor: float* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetLightColor")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3RequestCameraImageSetLightColor")] public static extern void b3RequestCameraImageSetLightColor(IntPtr commandHandle, ref float lightColor) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///lightDistance: float - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetLightDistance")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3RequestCameraImageSetLightDistance")] public static extern void b3RequestCameraImageSetLightDistance(IntPtr commandHandle, float lightDistance) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///lightAmbientCoeff: float - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetLightAmbientCoeff")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3RequestCameraImageSetLightAmbientCoeff")] public static extern void b3RequestCameraImageSetLightAmbientCoeff(IntPtr commandHandle, float lightAmbientCoeff) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///lightDiffuseCoeff: float - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetLightDiffuseCoeff")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3RequestCameraImageSetLightDiffuseCoeff")] public static extern void b3RequestCameraImageSetLightDiffuseCoeff(IntPtr commandHandle, float lightDiffuseCoeff) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///lightSpecularCoeff: float - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetLightSpecularCoeff")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3RequestCameraImageSetLightSpecularCoeff")] public static extern void b3RequestCameraImageSetLightSpecularCoeff(IntPtr commandHandle, float lightSpecularCoeff) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///hasShadow: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetShadow")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3RequestCameraImageSetShadow")] public static extern void b3RequestCameraImageSetShadow(IntPtr commandHandle, int hasShadow) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///renderer: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSelectRenderer")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3RequestCameraImageSelectRenderer")] public static extern void b3RequestCameraImageSelectRenderer(IntPtr commandHandle, int renderer) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///imageData: b3CameraImageData* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetCameraImageData")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetCameraImageData")] public static extern void b3GetCameraImageData(IntPtr physClient, ref b3CameraImageData imageData) ; @@ -1916,7 +1917,7 @@ public static extern void b3GetCameraImageData(IntPtr physClient, ref b3CameraI ///cameraTargetPosition: float* ///cameraUp: float* ///viewMatrix: float* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ComputeViewMatrixFromPositions")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ComputeViewMatrixFromPositions")] public static extern void b3ComputeViewMatrixFromPositions(ref float cameraPosition, ref float cameraTargetPosition, ref float cameraUp, ref float viewMatrix) ; @@ -1928,7 +1929,7 @@ public static extern void b3ComputeViewMatrixFromPositions(ref float cameraPosi ///roll: float ///upAxis: int ///viewMatrix: float* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ComputeViewMatrixFromYawPitchRoll")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ComputeViewMatrixFromYawPitchRoll")] public static extern void b3ComputeViewMatrixFromYawPitchRoll(ref float cameraTargetPosition, float distance, float yaw, float pitch, float roll, int upAxis, ref float viewMatrix) ; @@ -1937,7 +1938,7 @@ public static extern void b3ComputeViewMatrixFromYawPitchRoll(ref float cameraT ///cameraPosition: float* ///cameraTargetPosition: float* ///cameraUp: float* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ComputePositionFromViewMatrix")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ComputePositionFromViewMatrix")] public static extern void b3ComputePositionFromViewMatrix(ref float viewMatrix, ref float cameraPosition, ref float cameraTargetPosition, ref float cameraUp) ; @@ -1949,7 +1950,7 @@ public static extern void b3ComputePositionFromViewMatrix(ref float viewMatrix, ///nearVal: float ///farVal: float ///projectionMatrix: float* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ComputeProjectionMatrix")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ComputeProjectionMatrix")] public static extern void b3ComputeProjectionMatrix(float left, float right, float bottom, float top, float nearVal, float farVal, ref float projectionMatrix) ; @@ -1959,7 +1960,7 @@ public static extern void b3ComputeProjectionMatrix(float left, float right, fl ///nearVal: float ///farVal: float ///projectionMatrix: float* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ComputeProjectionMatrixFOV")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ComputeProjectionMatrixFOV")] public static extern void b3ComputeProjectionMatrixFOV(float fov, float aspect, float nearVal, float farVal, ref float projectionMatrix) ; @@ -1968,7 +1969,7 @@ public static extern void b3ComputeProjectionMatrixFOV(float fov, float aspect, ///cameraPosition: float* ///cameraTargetPosition: float* ///cameraUp: float* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetViewMatrix")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3RequestCameraImageSetViewMatrix")] public static extern void b3RequestCameraImageSetViewMatrix(IntPtr commandHandle, ref float cameraPosition, ref float cameraTargetPosition, ref float cameraUp) ; @@ -1980,7 +1981,7 @@ public static extern void b3RequestCameraImageSetViewMatrix(IntPtr commandHandl ///pitch: float ///roll: float ///upAxis: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetViewMatrix2")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3RequestCameraImageSetViewMatrix2")] public static extern void b3RequestCameraImageSetViewMatrix2(IntPtr commandHandle, ref float cameraTargetPosition, float distance, float yaw, float pitch, float roll, int upAxis) ; @@ -1992,7 +1993,7 @@ public static extern void b3RequestCameraImageSetViewMatrix2(IntPtr commandHand ///top: float ///nearVal: float ///farVal: float - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetProjectionMatrix")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3RequestCameraImageSetProjectionMatrix")] public static extern void b3RequestCameraImageSetProjectionMatrix(IntPtr commandHandle, float left, float right, float bottom, float top, float nearVal, float farVal) ; @@ -2002,96 +2003,96 @@ public static extern void b3RequestCameraImageSetProjectionMatrix(IntPtr comman ///aspect: float ///nearVal: float ///farVal: float - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetFOVProjectionMatrix")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3RequestCameraImageSetFOVProjectionMatrix")] public static extern void b3RequestCameraImageSetFOVProjectionMatrix(IntPtr commandHandle, float fov, float aspect, float nearVal, float farVal) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitRequestContactPointInformation")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitRequestContactPointInformation")] public static extern System.IntPtr b3InitRequestContactPointInformation(IntPtr physClient) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///bodyUniqueIdA: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetContactFilterBodyA")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3SetContactFilterBodyA")] public static extern void b3SetContactFilterBodyA(IntPtr commandHandle, int bodyUniqueIdA) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///bodyUniqueIdB: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetContactFilterBodyB")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3SetContactFilterBodyB")] public static extern void b3SetContactFilterBodyB(IntPtr commandHandle, int bodyUniqueIdB) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///linkIndexA: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetContactFilterLinkA")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3SetContactFilterLinkA")] public static extern void b3SetContactFilterLinkA(IntPtr commandHandle, int linkIndexA) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///linkIndexB: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetContactFilterLinkB")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3SetContactFilterLinkB")] public static extern void b3SetContactFilterLinkB(IntPtr commandHandle, int linkIndexB) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///contactPointData: b3ContactInformation* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetContactPointInformation")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetContactPointInformation")] public static extern void b3GetContactPointInformation(IntPtr physClient, ref b3ContactInformation contactPointData) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitClosestDistanceQuery")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitClosestDistanceQuery")] public static extern System.IntPtr b3InitClosestDistanceQuery(IntPtr physClient) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///bodyUniqueIdA: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetClosestDistanceFilterBodyA")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3SetClosestDistanceFilterBodyA")] public static extern void b3SetClosestDistanceFilterBodyA(IntPtr commandHandle, int bodyUniqueIdA) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///linkIndexA: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetClosestDistanceFilterLinkA")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3SetClosestDistanceFilterLinkA")] public static extern void b3SetClosestDistanceFilterLinkA(IntPtr commandHandle, int linkIndexA) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///bodyUniqueIdB: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetClosestDistanceFilterBodyB")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3SetClosestDistanceFilterBodyB")] public static extern void b3SetClosestDistanceFilterBodyB(IntPtr commandHandle, int bodyUniqueIdB) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///linkIndexB: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetClosestDistanceFilterLinkB")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3SetClosestDistanceFilterLinkB")] public static extern void b3SetClosestDistanceFilterLinkB(IntPtr commandHandle, int linkIndexB) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///distance: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetClosestDistanceThreshold")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3SetClosestDistanceThreshold")] public static extern void b3SetClosestDistanceThreshold(IntPtr commandHandle, double distance) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///contactPointInfo: b3ContactInformation* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetClosestPointInformation")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetClosestPointInformation")] public static extern void b3GetClosestPointInformation(IntPtr physClient, ref b3ContactInformation contactPointInfo) ; @@ -2099,41 +2100,41 @@ public static extern void b3GetClosestPointInformation(IntPtr physClient, ref b ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///aabbMin: double* ///aabbMax: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitAABBOverlapQuery")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitAABBOverlapQuery")] public static extern System.IntPtr b3InitAABBOverlapQuery(IntPtr physClient, ref double aabbMin, ref double aabbMax) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///data: b3AABBOverlapData* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetAABBOverlapResults")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetAABBOverlapResults")] public static extern void b3GetAABBOverlapResults(IntPtr physClient, ref b3AABBOverlapData data) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyUniqueIdA: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitRequestVisualShapeInformation")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitRequestVisualShapeInformation")] public static extern System.IntPtr b3InitRequestVisualShapeInformation(IntPtr physClient, int bodyUniqueIdA) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///visualShapeInfo: b3VisualShapeInformation* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetVisualShapeInformation")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetVisualShapeInformation")] public static extern void b3GetVisualShapeInformation(IntPtr physClient, ref b3VisualShapeInformation visualShapeInfo) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///filename: char* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitLoadTexture")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitLoadTexture")] public static extern System.IntPtr b3InitLoadTexture(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("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusTextureUniqueId")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetStatusTextureUniqueId")] public static extern int b3GetStatusTextureUniqueId(IntPtr statusHandle) ; @@ -2143,7 +2144,7 @@ public static extern int b3GetStatusTextureUniqueId(IntPtr statusHandle) ; ///width: int ///height: int ///rgbPixels: char* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateChangeTextureCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateChangeTextureCommandInit")] public static extern System.IntPtr b3CreateChangeTextureCommandInit(IntPtr physClient, int textureUniqueId, int width, int height, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string rgbPixels) ; @@ -2153,27 +2154,27 @@ public static extern System.IntPtr b3CreateChangeTextureCommandInit(IntPtr phys ///jointIndex: int ///shapeIndex: int ///textureUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitUpdateVisualShape")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitUpdateVisualShape")] public static extern System.IntPtr b3InitUpdateVisualShape(IntPtr physClient, int bodyUniqueId, int jointIndex, int shapeIndex, int textureUniqueId) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///rgbaColor: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3UpdateVisualShapeRGBAColor")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3UpdateVisualShapeRGBAColor")] public static extern void b3UpdateVisualShapeRGBAColor(IntPtr commandHandle, ref double rgbaColor) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///specularColor: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3UpdateVisualShapeSpecularColor")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3UpdateVisualShapeSpecularColor")] public static extern void b3UpdateVisualShapeSpecularColor(IntPtr commandHandle, ref double specularColor) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitPhysicsParamCommand")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitPhysicsParamCommand")] public static extern System.IntPtr b3InitPhysicsParamCommand(IntPtr physClient) ; @@ -2182,131 +2183,131 @@ public static extern System.IntPtr b3InitPhysicsParamCommand(IntPtr physClient) ///gravx: double ///gravy: double ///gravz: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetGravity")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3PhysicsParamSetGravity")] public static extern int b3PhysicsParamSetGravity(IntPtr commandHandle, double gravx, double gravy, double gravz) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///timeStep: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetTimeStep")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3PhysicsParamSetTimeStep")] public static extern int b3PhysicsParamSetTimeStep(IntPtr commandHandle, double timeStep) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///defaultContactERP: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetDefaultContactERP")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3PhysicsParamSetDefaultContactERP")] public static extern int b3PhysicsParamSetDefaultContactERP(IntPtr commandHandle, double defaultContactERP) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///defaultNonContactERP: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetDefaultNonContactERP")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3PhysicsParamSetDefaultNonContactERP")] public static extern int b3PhysicsParamSetDefaultNonContactERP(IntPtr commandHandle, double defaultNonContactERP) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///frictionERP: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetDefaultFrictionERP")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3PhysicsParamSetDefaultFrictionERP")] public static extern int b3PhysicsParamSetDefaultFrictionERP(IntPtr commandHandle, double frictionERP) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///numSubSteps: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetNumSubSteps")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3PhysicsParamSetNumSubSteps")] public static extern int b3PhysicsParamSetNumSubSteps(IntPtr commandHandle, int numSubSteps) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///enableRealTimeSimulation: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetRealTimeSimulation")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3PhysicsParamSetRealTimeSimulation")] public static extern int b3PhysicsParamSetRealTimeSimulation(IntPtr commandHandle, int enableRealTimeSimulation) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///numSolverIterations: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetNumSolverIterations")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3PhysicsParamSetNumSolverIterations")] public static extern int b3PhysicsParamSetNumSolverIterations(IntPtr commandHandle, int numSolverIterations) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///filterMode: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetCollisionFilterMode")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3PhysicsParamSetCollisionFilterMode")] public static extern int b3PhysicsParamSetCollisionFilterMode(IntPtr commandHandle, int filterMode) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///useSplitImpulse: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetUseSplitImpulse")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3PhysicsParamSetUseSplitImpulse")] public static extern int b3PhysicsParamSetUseSplitImpulse(IntPtr commandHandle, int useSplitImpulse) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///splitImpulsePenetrationThreshold: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetSplitImpulsePenetrationThreshold")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3PhysicsParamSetSplitImpulsePenetrationThreshold")] public static extern int b3PhysicsParamSetSplitImpulsePenetrationThreshold(IntPtr commandHandle, double splitImpulsePenetrationThreshold) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///contactBreakingThreshold: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetContactBreakingThreshold")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3PhysicsParamSetContactBreakingThreshold")] public static extern int b3PhysicsParamSetContactBreakingThreshold(IntPtr commandHandle, double contactBreakingThreshold) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///maxNumCmdPer1ms: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetMaxNumCommandsPer1ms")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3PhysicsParamSetMaxNumCommandsPer1ms")] public static extern int b3PhysicsParamSetMaxNumCommandsPer1ms(IntPtr commandHandle, int maxNumCmdPer1ms) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///enableFileCaching: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetEnableFileCaching")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3PhysicsParamSetEnableFileCaching")] public static extern int b3PhysicsParamSetEnableFileCaching(IntPtr commandHandle, int enableFileCaching) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///restitutionVelocityThreshold: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetRestitutionVelocityThreshold")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3PhysicsParamSetRestitutionVelocityThreshold")] public static extern int b3PhysicsParamSetRestitutionVelocityThreshold(IntPtr commandHandle, double restitutionVelocityThreshold) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///flags: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetInternalSimFlags")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3PhysicsParamSetInternalSimFlags")] public static extern int b3PhysicsParamSetInternalSimFlags(IntPtr commandHandle, int flags) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitStepSimulationCommand")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitStepSimulationCommand")] public static extern System.IntPtr b3InitStepSimulationCommand(IntPtr physClient) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitResetSimulationCommand")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitResetSimulationCommand")] public static extern System.IntPtr b3InitResetSimulationCommand(IntPtr physClient) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///urdfFileName: char* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadUrdfCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadUrdfCommandInit")] public static extern System.IntPtr b3LoadUrdfCommandInit(IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string urdfFileName) ; @@ -2315,7 +2316,7 @@ public static extern System.IntPtr b3LoadUrdfCommandInit(IntPtr physClient, [Sy ///startPosX: double ///startPosY: double ///startPosZ: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadUrdfCommandSetStartPosition")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadUrdfCommandSetStartPosition")] public static extern int b3LoadUrdfCommandSetStartPosition(IntPtr commandHandle, double startPosX, double startPosY, double startPosZ) ; @@ -2325,63 +2326,63 @@ public static extern int b3LoadUrdfCommandSetStartPosition(IntPtr commandHandle ///startOrnY: double ///startOrnZ: double ///startOrnW: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadUrdfCommandSetStartOrientation")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadUrdfCommandSetStartOrientation")] public static extern int b3LoadUrdfCommandSetStartOrientation(IntPtr commandHandle, double startOrnX, double startOrnY, double startOrnZ, double startOrnW) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///useMultiBody: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadUrdfCommandSetUseMultiBody")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadUrdfCommandSetUseMultiBody")] public static extern int b3LoadUrdfCommandSetUseMultiBody(IntPtr commandHandle, int useMultiBody) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///useFixedBase: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadUrdfCommandSetUseFixedBase")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadUrdfCommandSetUseFixedBase")] public static extern int b3LoadUrdfCommandSetUseFixedBase(IntPtr commandHandle, int useFixedBase) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///flags: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadUrdfCommandSetFlags")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadUrdfCommandSetFlags")] public static extern int b3LoadUrdfCommandSetFlags(IntPtr commandHandle, int flags) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///globalScaling: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadUrdfCommandSetGlobalScaling")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadUrdfCommandSetGlobalScaling")] public static extern int b3LoadUrdfCommandSetGlobalScaling(IntPtr commandHandle, double globalScaling) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///fileName: char* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadBulletCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadBulletCommandInit")] public static extern System.IntPtr b3LoadBulletCommandInit(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("pybullet_vs2010_x64_release.dll", EntryPoint="b3SaveBulletCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3SaveBulletCommandInit")] public static extern System.IntPtr b3SaveBulletCommandInit(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("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadMJCFCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadMJCFCommandInit")] public static extern System.IntPtr b3LoadMJCFCommandInit(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("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadMJCFCommandSetFlags")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadMJCFCommandSetFlags")] public static extern void b3LoadMJCFCommandSetFlags(IntPtr commandHandle, int flags) ; @@ -2391,7 +2392,7 @@ public static extern void b3LoadMJCFCommandSetFlags(IntPtr commandHandle, int f ///jointPositionsQ: double* ///jointVelocitiesQdot: double* ///jointAccelerations: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CalculateInverseDynamicsCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CalculateInverseDynamicsCommandInit")] public static extern System.IntPtr b3CalculateInverseDynamicsCommandInit(IntPtr physClient, int bodyIndex, ref double jointPositionsQ, ref double jointVelocitiesQdot, ref double jointAccelerations) ; @@ -2400,7 +2401,7 @@ public static extern System.IntPtr b3CalculateInverseDynamicsCommandInit(IntPtr ///bodyUniqueId: int* ///dofCount: int* ///jointForces: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusInverseDynamicsJointForces")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetStatusInverseDynamicsJointForces")] public static extern int b3GetStatusInverseDynamicsJointForces(IntPtr statusHandle, ref int bodyUniqueId, ref int dofCount, ref double jointForces) ; @@ -2412,7 +2413,7 @@ public static extern int b3GetStatusInverseDynamicsJointForces(IntPtr statusHan ///jointPositionsQ: double* ///jointVelocitiesQdot: double* ///jointAccelerations: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CalculateJacobianCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CalculateJacobianCommandInit")] public static extern System.IntPtr b3CalculateJacobianCommandInit(IntPtr physClient, int bodyIndex, int linkIndex, ref double localPosition, ref double jointPositionsQ, ref double jointVelocitiesQdot, ref double jointAccelerations) ; @@ -2421,14 +2422,14 @@ public static extern System.IntPtr b3CalculateJacobianCommandInit(IntPtr physCl ///dofCount: int* ///linearJacobian: double* ///angularJacobian: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusJacobian")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetStatusJacobian")] public static extern int b3GetStatusJacobian(IntPtr statusHandle, ref int dofCount, ref double linearJacobian, ref double angularJacobian) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyIndex: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CalculateInverseKinematicsCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CalculateInverseKinematicsCommandInit")] public static extern System.IntPtr b3CalculateInverseKinematicsCommandInit(IntPtr physClient, int bodyIndex) ; @@ -2436,7 +2437,7 @@ public static extern System.IntPtr b3CalculateInverseKinematicsCommandInit(IntP ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///endEffectorLinkIndex: int ///targetPosition: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CalculateInverseKinematicsAddTargetPurePosition")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CalculateInverseKinematicsAddTargetPurePosition")] public static extern void b3CalculateInverseKinematicsAddTargetPurePosition(IntPtr commandHandle, int endEffectorLinkIndex, ref double targetPosition) ; @@ -2445,7 +2446,7 @@ public static extern void b3CalculateInverseKinematicsAddTargetPurePosition(Int ///endEffectorLinkIndex: int ///targetPosition: double* ///targetOrientation: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CalculateInverseKinematicsAddTargetPositionWithOrientation")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CalculateInverseKinematicsAddTargetPositionWithOrientation")] public static extern void b3CalculateInverseKinematicsAddTargetPositionWithOrientation(IntPtr commandHandle, int endEffectorLinkIndex, ref double targetPosition, ref double targetOrientation) ; @@ -2458,7 +2459,7 @@ public static extern void b3CalculateInverseKinematicsAddTargetPositionWithOrie ///upperLimit: double* ///jointRange: double* ///restPose: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CalculateInverseKinematicsPosWithNullSpaceVel")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CalculateInverseKinematicsPosWithNullSpaceVel")] public static extern void b3CalculateInverseKinematicsPosWithNullSpaceVel(IntPtr commandHandle, int numDof, int endEffectorLinkIndex, ref double targetPosition, ref double lowerLimit, ref double upperLimit, ref double jointRange, ref double restPose) ; @@ -2472,7 +2473,7 @@ public static extern void b3CalculateInverseKinematicsPosWithNullSpaceVel(IntPt ///upperLimit: double* ///jointRange: double* ///restPose: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CalculateInverseKinematicsPosOrnWithNullSpaceVel")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CalculateInverseKinematicsPosOrnWithNullSpaceVel")] public static extern void b3CalculateInverseKinematicsPosOrnWithNullSpaceVel(IntPtr commandHandle, int numDof, int endEffectorLinkIndex, ref double targetPosition, ref double targetOrientation, ref double lowerLimit, ref double upperLimit, ref double jointRange, ref double restPose) ; @@ -2480,7 +2481,7 @@ public static extern void b3CalculateInverseKinematicsPosOrnWithNullSpaceVel(In ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///numDof: int ///jointDampingCoeff: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CalculateInverseKinematicsSetJointDamping")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CalculateInverseKinematicsSetJointDamping")] public static extern void b3CalculateInverseKinematicsSetJointDamping(IntPtr commandHandle, int numDof, ref double jointDampingCoeff) ; @@ -2489,42 +2490,42 @@ public static extern void b3CalculateInverseKinematicsSetJointDamping(IntPtr co ///bodyUniqueId: int* ///dofCount: int* ///jointPositions: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusInverseKinematicsJointPositions")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetStatusInverseKinematicsJointPositions")] public static extern int b3GetStatusInverseKinematicsJointPositions(IntPtr statusHandle, ref int bodyUniqueId, ref int dofCount, ref double jointPositions) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///sdfFileName: char* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadSdfCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadSdfCommandInit")] public static extern System.IntPtr b3LoadSdfCommandInit(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("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadSdfCommandSetUseMultiBody")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadSdfCommandSetUseMultiBody")] public static extern int b3LoadSdfCommandSetUseMultiBody(IntPtr commandHandle, int useMultiBody) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///globalScaling: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadSdfCommandSetUseGlobalScaling")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadSdfCommandSetUseGlobalScaling")] public static extern int b3LoadSdfCommandSetUseGlobalScaling(IntPtr commandHandle, double globalScaling) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///sdfFileName: char* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SaveWorldCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3SaveWorldCommandInit")] public static extern System.IntPtr b3SaveWorldCommandInit(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("pybullet_vs2010_x64_release.dll", EntryPoint="b3JointControlCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3JointControlCommandInit")] public static extern System.IntPtr b3JointControlCommandInit(IntPtr physClient, int controlMode) ; @@ -2532,7 +2533,7 @@ public static extern System.IntPtr b3JointControlCommandInit(IntPtr physClient, ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyUniqueId: int ///controlMode: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3JointControlCommandInit2")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3JointControlCommandInit2")] public static extern System.IntPtr b3JointControlCommandInit2(IntPtr physClient, int bodyUniqueId, int controlMode) ; @@ -2540,7 +2541,7 @@ public static extern System.IntPtr b3JointControlCommandInit2(IntPtr physClient ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///qIndex: int ///value: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3JointControlSetDesiredPosition")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3JointControlSetDesiredPosition")] public static extern int b3JointControlSetDesiredPosition(IntPtr commandHandle, int qIndex, double value) ; @@ -2548,7 +2549,7 @@ public static extern int b3JointControlSetDesiredPosition(IntPtr commandHandle, ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///dofIndex: int ///value: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3JointControlSetKp")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3JointControlSetKp")] public static extern int b3JointControlSetKp(IntPtr commandHandle, int dofIndex, double value) ; @@ -2556,7 +2557,7 @@ public static extern int b3JointControlSetKp(IntPtr commandHandle, int dofIndex ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///dofIndex: int ///value: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3JointControlSetKd")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3JointControlSetKd")] public static extern int b3JointControlSetKd(IntPtr commandHandle, int dofIndex, double value) ; @@ -2564,7 +2565,7 @@ public static extern int b3JointControlSetKd(IntPtr commandHandle, int dofIndex ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///dofIndex: int ///value: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3JointControlSetDesiredVelocity")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3JointControlSetDesiredVelocity")] public static extern int b3JointControlSetDesiredVelocity(IntPtr commandHandle, int dofIndex, double value) ; @@ -2572,7 +2573,7 @@ public static extern int b3JointControlSetDesiredVelocity(IntPtr commandHandle, ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///dofIndex: int ///value: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3JointControlSetMaximumForce")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3JointControlSetMaximumForce")] public static extern int b3JointControlSetMaximumForce(IntPtr commandHandle, int dofIndex, double value) ; @@ -2580,27 +2581,27 @@ public static extern int b3JointControlSetMaximumForce(IntPtr commandHandle, in ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///dofIndex: int ///value: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3JointControlSetDesiredForceTorque")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3JointControlSetDesiredForceTorque")] public static extern int b3JointControlSetDesiredForceTorque(IntPtr commandHandle, int dofIndex, double value) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateCollisionShapeCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateCollisionShapeCommandInit")] public static extern System.IntPtr b3CreateCollisionShapeCommandInit(IntPtr physClient) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///radius: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateCollisionShapeAddSphere")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateCollisionShapeAddSphere")] public static extern int b3CreateCollisionShapeAddSphere(IntPtr commandHandle, double radius) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///halfExtents: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateCollisionShapeAddBox")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateCollisionShapeAddBox")] public static extern int b3CreateCollisionShapeAddBox(IntPtr commandHandle, ref double halfExtents) ; @@ -2608,7 +2609,7 @@ public static extern int b3CreateCollisionShapeAddBox(IntPtr commandHandle, ref ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///radius: double ///height: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateCollisionShapeAddCapsule")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateCollisionShapeAddCapsule")] public static extern int b3CreateCollisionShapeAddCapsule(IntPtr commandHandle, double radius, double height) ; @@ -2616,7 +2617,7 @@ public static extern int b3CreateCollisionShapeAddCapsule(IntPtr commandHandle, ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///radius: double ///height: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateCollisionShapeAddCylinder")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateCollisionShapeAddCylinder")] public static extern int b3CreateCollisionShapeAddCylinder(IntPtr commandHandle, double radius, double height) ; @@ -2624,7 +2625,7 @@ public static extern int b3CreateCollisionShapeAddCylinder(IntPtr commandHandle ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///planeNormal: double* ///planeConstant: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateCollisionShapeAddPlane")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateCollisionShapeAddPlane")] public static extern int b3CreateCollisionShapeAddPlane(IntPtr commandHandle, ref double planeNormal, double planeConstant) ; @@ -2632,7 +2633,7 @@ public static extern int b3CreateCollisionShapeAddPlane(IntPtr commandHandle, r ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///fileName: char* ///meshScale: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateCollisionShapeAddMesh")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateCollisionShapeAddMesh")] public static extern int b3CreateCollisionShapeAddMesh(IntPtr commandHandle, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName, ref double meshScale) ; @@ -2640,7 +2641,7 @@ public static extern int b3CreateCollisionShapeAddMesh(IntPtr commandHandle, [S ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///shapeIndex: int ///flags: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateCollisionSetFlag")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateCollisionSetFlag")] public static extern void b3CreateCollisionSetFlag(IntPtr commandHandle, int shapeIndex, int flags) ; @@ -2649,31 +2650,31 @@ public static extern void b3CreateCollisionSetFlag(IntPtr commandHandle, int sh ///shapeIndex: int ///childPosition: double* ///childOrientation: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateCollisionShapeSetChildTransform")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateCollisionShapeSetChildTransform")] public static extern void b3CreateCollisionShapeSetChildTransform(IntPtr commandHandle, int shapeIndex, ref double childPosition, ref double childOrientation) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusCollisionShapeUniqueId")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetStatusCollisionShapeUniqueId")] public static extern int b3GetStatusCollisionShapeUniqueId(IntPtr statusHandle) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateVisualShapeCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateVisualShapeCommandInit")] public static extern System.IntPtr b3CreateVisualShapeCommandInit(IntPtr physClient) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusVisualShapeUniqueId")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetStatusVisualShapeUniqueId")] public static extern int b3GetStatusVisualShapeUniqueId(IntPtr statusHandle) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateMultiBodyCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateMultiBodyCommandInit")] public static extern System.IntPtr b3CreateMultiBodyCommandInit(IntPtr physClient) ; @@ -2686,7 +2687,7 @@ public static extern System.IntPtr b3CreateMultiBodyCommandInit(IntPtr physClie ///baseOrientation: double* ///baseInertialFramePosition: double* ///baseInertialFrameOrientation: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateMultiBodyBase")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateMultiBodyBase")] public static extern int b3CreateMultiBodyBase(IntPtr commandHandle, double mass, int collisionShapeUnique, int visualShapeUniqueId, ref double basePosition, ref double baseOrientation, ref double baseInertialFramePosition, ref double baseInertialFrameOrientation) ; @@ -2702,19 +2703,19 @@ public static extern int b3CreateMultiBodyBase(IntPtr commandHandle, double mas ///linkParentIndex: int ///linkJointType: int ///linkJointAxis: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateMultiBodyLink")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateMultiBodyLink")] public static extern int b3CreateMultiBodyLink(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("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateMultiBodyUseMaximalCoordinates")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateMultiBodyUseMaximalCoordinates")] public static extern void b3CreateMultiBodyUseMaximalCoordinates(IntPtr commandHandle) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateBoxShapeCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateBoxShapeCommandInit")] public static extern System.IntPtr b3CreateBoxShapeCommandInit(IntPtr physClient) ; @@ -2723,7 +2724,7 @@ public static extern System.IntPtr b3CreateBoxShapeCommandInit(IntPtr physClien ///startPosX: double ///startPosY: double ///startPosZ: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateBoxCommandSetStartPosition")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateBoxCommandSetStartPosition")] public static extern int b3CreateBoxCommandSetStartPosition(IntPtr commandHandle, double startPosX, double startPosY, double startPosZ) ; @@ -2733,7 +2734,7 @@ public static extern int b3CreateBoxCommandSetStartPosition(IntPtr commandHandl ///startOrnY: double ///startOrnZ: double ///startOrnW: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateBoxCommandSetStartOrientation")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateBoxCommandSetStartOrientation")] public static extern int b3CreateBoxCommandSetStartOrientation(IntPtr commandHandle, double startOrnX, double startOrnY, double startOrnZ, double startOrnW) ; @@ -2742,21 +2743,21 @@ public static extern int b3CreateBoxCommandSetStartOrientation(IntPtr commandHa ///halfExtentsX: double ///halfExtentsY: double ///halfExtentsZ: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateBoxCommandSetHalfExtents")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateBoxCommandSetHalfExtents")] public static extern int b3CreateBoxCommandSetHalfExtents(IntPtr commandHandle, double halfExtentsX, double halfExtentsY, double halfExtentsZ) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///mass: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateBoxCommandSetMass")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateBoxCommandSetMass")] public static extern int b3CreateBoxCommandSetMass(IntPtr commandHandle, double mass) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///collisionShapeType: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateBoxCommandSetCollisionShapeType")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateBoxCommandSetCollisionShapeType")] public static extern int b3CreateBoxCommandSetCollisionShapeType(IntPtr commandHandle, int collisionShapeType) ; @@ -2766,14 +2767,14 @@ public static extern int b3CreateBoxCommandSetCollisionShapeType(IntPtr command ///green: double ///blue: double ///alpha: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateBoxCommandSetColorRGBA")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateBoxCommandSetColorRGBA")] public static extern int b3CreateBoxCommandSetColorRGBA(IntPtr commandHandle, double red, double green, double blue, double alpha) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyIndex: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreatePoseCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreatePoseCommandInit")] public static extern System.IntPtr b3CreatePoseCommandInit(IntPtr physClient, int bodyIndex) ; @@ -2782,7 +2783,7 @@ public static extern System.IntPtr b3CreatePoseCommandInit(IntPtr physClient, i ///startPosX: double ///startPosY: double ///startPosZ: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreatePoseCommandSetBasePosition")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreatePoseCommandSetBasePosition")] public static extern int b3CreatePoseCommandSetBasePosition(IntPtr commandHandle, double startPosX, double startPosY, double startPosZ) ; @@ -2792,21 +2793,21 @@ public static extern int b3CreatePoseCommandSetBasePosition(IntPtr commandHandl ///startOrnY: double ///startOrnZ: double ///startOrnW: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreatePoseCommandSetBaseOrientation")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreatePoseCommandSetBaseOrientation")] public static extern int b3CreatePoseCommandSetBaseOrientation(IntPtr commandHandle, double startOrnX, double startOrnY, double startOrnZ, double startOrnW) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///linVel: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreatePoseCommandSetBaseLinearVelocity")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreatePoseCommandSetBaseLinearVelocity")] public static extern int b3CreatePoseCommandSetBaseLinearVelocity(IntPtr commandHandle, ref double linVel) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///angVel: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreatePoseCommandSetBaseAngularVelocity")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreatePoseCommandSetBaseAngularVelocity")] public static extern int b3CreatePoseCommandSetBaseAngularVelocity(IntPtr commandHandle, ref double angVel) ; @@ -2814,7 +2815,7 @@ public static extern int b3CreatePoseCommandSetBaseAngularVelocity(IntPtr comma ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///numJointPositions: int ///jointPositions: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreatePoseCommandSetJointPositions")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreatePoseCommandSetJointPositions")] public static extern int b3CreatePoseCommandSetJointPositions(IntPtr commandHandle, int numJointPositions, ref double jointPositions) ; @@ -2823,7 +2824,7 @@ public static extern int b3CreatePoseCommandSetJointPositions(IntPtr commandHan ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///jointIndex: int ///jointPosition: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreatePoseCommandSetJointPosition")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreatePoseCommandSetJointPosition")] public static extern int b3CreatePoseCommandSetJointPosition(IntPtr physClient, IntPtr commandHandle, int jointIndex, double jointPosition) ; @@ -2832,7 +2833,7 @@ public static extern int b3CreatePoseCommandSetJointPosition(IntPtr physClient, ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///numJointVelocities: int ///jointVelocities: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreatePoseCommandSetJointVelocities")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreatePoseCommandSetJointVelocities")] public static extern int b3CreatePoseCommandSetJointVelocities(IntPtr physClient, IntPtr commandHandle, int numJointVelocities, ref double jointVelocities) ; @@ -2841,14 +2842,14 @@ public static extern int b3CreatePoseCommandSetJointVelocities(IntPtr physClien ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///jointIndex: int ///jointVelocity: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreatePoseCommandSetJointVelocity")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreatePoseCommandSetJointVelocity")] public static extern int b3CreatePoseCommandSetJointVelocity(IntPtr physClient, IntPtr commandHandle, int jointIndex, double jointVelocity) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateSensorCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateSensorCommandInit")] public static extern System.IntPtr b3CreateSensorCommandInit(IntPtr physClient, int bodyUniqueId) ; @@ -2856,7 +2857,7 @@ public static extern System.IntPtr b3CreateSensorCommandInit(IntPtr physClient, ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///jointIndex: int ///enable: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateSensorEnable6DofJointForceTorqueSensor")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateSensorEnable6DofJointForceTorqueSensor")] public static extern int b3CreateSensorEnable6DofJointForceTorqueSensor(IntPtr commandHandle, int jointIndex, int enable) ; @@ -2864,28 +2865,28 @@ public static extern int b3CreateSensorEnable6DofJointForceTorqueSensor(IntPtr ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///linkIndex: int ///enable: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateSensorEnableIMUForLink")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateSensorEnableIMUForLink")] public static extern int b3CreateSensorEnableIMUForLink(IntPtr commandHandle, int linkIndex, int enable) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestActualStateCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3RequestActualStateCommandInit")] public static extern System.IntPtr b3RequestActualStateCommandInit(IntPtr physClient, int bodyUniqueId) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///computeLinkVelocity: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestActualStateCommandComputeLinkVelocity")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3RequestActualStateCommandComputeLinkVelocity")] public static extern int b3RequestActualStateCommandComputeLinkVelocity(IntPtr commandHandle, int computeLinkVelocity) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///computeForwardKinematics: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestActualStateCommandComputeForwardKinematics")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3RequestActualStateCommandComputeForwardKinematics")] public static extern int b3RequestActualStateCommandComputeForwardKinematics(IntPtr commandHandle, int computeForwardKinematics) ; @@ -2894,7 +2895,7 @@ public static extern int b3RequestActualStateCommandComputeForwardKinematics(In ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* ///jointIndex: int ///state: b3JointSensorState* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetJointState")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetJointState")] public static extern int b3GetJointState(IntPtr physClient, IntPtr statusHandle, int jointIndex, ref b3JointSensorState state) ; @@ -2903,7 +2904,7 @@ public static extern int b3GetJointState(IntPtr physClient, IntPtr statusHandle ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* ///linkIndex: int ///state: b3LinkState* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetLinkState")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetLinkState")] public static extern int b3GetLinkState(IntPtr physClient, IntPtr statusHandle, int linkIndex, ref b3LinkState state) ; @@ -2915,7 +2916,7 @@ public static extern int b3GetLinkState(IntPtr physClient, IntPtr statusHandle, ///rayToWorldX: double ///rayToWorldY: double ///rayToWorldZ: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PickBody")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3PickBody")] public static extern System.IntPtr b3PickBody(IntPtr physClient, double rayFromWorldX, double rayFromWorldY, double rayFromWorldZ, double rayToWorldX, double rayToWorldY, double rayToWorldZ) ; @@ -2927,13 +2928,13 @@ public static extern System.IntPtr b3PickBody(IntPtr physClient, double rayFrom ///rayToWorldX: double ///rayToWorldY: double ///rayToWorldZ: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3MovePickedBody")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3MovePickedBody")] public static extern System.IntPtr b3MovePickedBody(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("pybullet_vs2010_x64_release.dll", EntryPoint="b3RemovePickingConstraint")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3RemovePickingConstraint")] public static extern System.IntPtr b3RemovePickingConstraint(IntPtr physClient) ; @@ -2945,13 +2946,13 @@ public static extern System.IntPtr b3RemovePickingConstraint(IntPtr physClient) ///rayToWorldX: double ///rayToWorldY: double ///rayToWorldZ: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateRaycastCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateRaycastCommandInit")] public static extern System.IntPtr b3CreateRaycastCommandInit(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("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateRaycastBatchCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateRaycastBatchCommandInit")] public static extern System.IntPtr b3CreateRaycastBatchCommandInit(IntPtr physClient) ; @@ -2959,20 +2960,20 @@ public static extern System.IntPtr b3CreateRaycastBatchCommandInit(IntPtr physC ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///rayFromWorld: double* ///rayToWorld: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RaycastBatchAddRay")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3RaycastBatchAddRay")] public static extern void b3RaycastBatchAddRay(IntPtr commandHandle, ref double rayFromWorld, ref double rayToWorld) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///raycastInfo: b3RaycastInformation* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetRaycastInformation")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetRaycastInformation")] public static extern void b3GetRaycastInformation(IntPtr physClient, ref b3RaycastInformation raycastInfo) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ApplyExternalForceCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ApplyExternalForceCommandInit")] public static extern System.IntPtr b3ApplyExternalForceCommandInit(IntPtr physClient) ; @@ -2983,7 +2984,7 @@ public static extern System.IntPtr b3ApplyExternalForceCommandInit(IntPtr physC ///force: double* ///position: double* ///flag: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ApplyExternalForce")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ApplyExternalForce")] public static extern void b3ApplyExternalForce(IntPtr commandHandle, int bodyUniqueId, int linkId, ref double force, ref double position, int flag) ; @@ -2993,120 +2994,120 @@ public static extern void b3ApplyExternalForce(IntPtr commandHandle, int bodyUn ///linkId: int ///torque: double* ///flag: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ApplyExternalTorque")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ApplyExternalTorque")] public static extern void b3ApplyExternalTorque(IntPtr commandHandle, int bodyUniqueId, int linkId, ref double torque, int flag) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadBunnyCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadBunnyCommandInit")] public static extern System.IntPtr b3LoadBunnyCommandInit(IntPtr physClient) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///scale: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadBunnySetScale")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadBunnySetScale")] public static extern int b3LoadBunnySetScale(IntPtr commandHandle, double scale) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///mass: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadBunnySetMass")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadBunnySetMass")] public static extern int b3LoadBunnySetMass(IntPtr commandHandle, double mass) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///collisionMargin: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadBunnySetCollisionMargin")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadBunnySetCollisionMargin")] public static extern int b3LoadBunnySetCollisionMargin(IntPtr commandHandle, double collisionMargin) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestVREventsCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3RequestVREventsCommandInit")] public static extern System.IntPtr b3RequestVREventsCommandInit(IntPtr physClient) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///deviceTypeFilter: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3VREventsSetDeviceTypeFilter")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3VREventsSetDeviceTypeFilter")] public static extern void b3VREventsSetDeviceTypeFilter(IntPtr commandHandle, int deviceTypeFilter) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///vrEventsData: b3VREventsData* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetVREventsData")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetVREventsData")] public static extern void b3GetVREventsData(IntPtr physClient, ref b3VREventsData vrEventsData) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetVRCameraStateCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3SetVRCameraStateCommandInit")] public static extern System.IntPtr b3SetVRCameraStateCommandInit(IntPtr physClient) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///rootPos: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetVRCameraRootPosition")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3SetVRCameraRootPosition")] public static extern int b3SetVRCameraRootPosition(IntPtr commandHandle, ref double rootPos) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///rootOrn: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetVRCameraRootOrientation")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3SetVRCameraRootOrientation")] public static extern int b3SetVRCameraRootOrientation(IntPtr commandHandle, ref double rootOrn) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///objectUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetVRCameraTrackingObject")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3SetVRCameraTrackingObject")] public static extern int b3SetVRCameraTrackingObject(IntPtr commandHandle, int objectUniqueId) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///flag: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetVRCameraTrackingObjectFlag")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3SetVRCameraTrackingObjectFlag")] public static extern int b3SetVRCameraTrackingObjectFlag(IntPtr commandHandle, int flag) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestKeyboardEventsCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3RequestKeyboardEventsCommandInit")] public static extern System.IntPtr b3RequestKeyboardEventsCommandInit(IntPtr physClient) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///keyboardEventsData: b3KeyboardEventsData* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetKeyboardEventsData")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetKeyboardEventsData")] public static extern void b3GetKeyboardEventsData(IntPtr physClient, ref b3KeyboardEventsData keyboardEventsData) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestMouseEventsCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3RequestMouseEventsCommandInit")] public static extern System.IntPtr b3RequestMouseEventsCommandInit(IntPtr physClient) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///mouseEventsData: b3MouseEventsData* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetMouseEventsData")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetMouseEventsData")] public static extern void b3GetMouseEventsData(IntPtr physClient, ref b3MouseEventsData mouseEventsData) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3StateLoggingCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3StateLoggingCommandInit")] public static extern System.IntPtr b3StateLoggingCommandInit(IntPtr physClient) ; @@ -3114,110 +3115,110 @@ public static extern System.IntPtr b3StateLoggingCommandInit(IntPtr physClient) ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///loggingType: int ///fileName: char* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3StateLoggingStart")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3StateLoggingStart")] public static extern int b3StateLoggingStart(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("pybullet_vs2010_x64_release.dll", EntryPoint="b3StateLoggingAddLoggingObjectUniqueId")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3StateLoggingAddLoggingObjectUniqueId")] public static extern int b3StateLoggingAddLoggingObjectUniqueId(IntPtr commandHandle, int objectUniqueId) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///maxLogDof: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3StateLoggingSetMaxLogDof")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3StateLoggingSetMaxLogDof")] public static extern int b3StateLoggingSetMaxLogDof(IntPtr commandHandle, int maxLogDof) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///linkIndexA: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3StateLoggingSetLinkIndexA")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3StateLoggingSetLinkIndexA")] public static extern int b3StateLoggingSetLinkIndexA(IntPtr commandHandle, int linkIndexA) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///linkIndexB: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3StateLoggingSetLinkIndexB")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3StateLoggingSetLinkIndexB")] public static extern int b3StateLoggingSetLinkIndexB(IntPtr commandHandle, int linkIndexB) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///bodyAUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3StateLoggingSetBodyAUniqueId")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3StateLoggingSetBodyAUniqueId")] public static extern int b3StateLoggingSetBodyAUniqueId(IntPtr commandHandle, int bodyAUniqueId) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///bodyBUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3StateLoggingSetBodyBUniqueId")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3StateLoggingSetBodyBUniqueId")] public static extern int b3StateLoggingSetBodyBUniqueId(IntPtr commandHandle, int bodyBUniqueId) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///deviceTypeFilter: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3StateLoggingSetDeviceTypeFilter")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3StateLoggingSetDeviceTypeFilter")] public static extern int b3StateLoggingSetDeviceTypeFilter(IntPtr commandHandle, int deviceTypeFilter) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///logFlags: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3StateLoggingSetLogFlags")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3StateLoggingSetLogFlags")] public static extern int b3StateLoggingSetLogFlags(IntPtr commandHandle, int logFlags) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusLoggingUniqueId")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetStatusLoggingUniqueId")] public static extern int b3GetStatusLoggingUniqueId(IntPtr statusHandle) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///loggingUid: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3StateLoggingStop")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3StateLoggingStop")] public static extern int b3StateLoggingStop(IntPtr commandHandle, int loggingUid) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///name: char* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ProfileTimingCommandInit")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ProfileTimingCommandInit")] public static extern System.IntPtr b3ProfileTimingCommandInit(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("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetProfileTimingDuractionInMicroSeconds")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3SetProfileTimingDuractionInMicroSeconds")] public static extern void b3SetProfileTimingDuractionInMicroSeconds(IntPtr commandHandle, int duration) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///timeOutInSeconds: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetTimeOut")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3SetTimeOut")] public static extern void b3SetTimeOut(IntPtr physClient, double timeOutInSeconds) ; /// Return Type: double ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetTimeOut")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetTimeOut")] public static extern double b3GetTimeOut(IntPtr physClient) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///path: char* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetAdditionalSearchPath")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3SetAdditionalSearchPath")] public static extern System.IntPtr b3SetAdditionalSearchPath(IntPtr physClient, System.IntPtr path) ; @@ -3228,7 +3229,7 @@ public static extern System.IntPtr b3SetAdditionalSearchPath(IntPtr physClient, ///ornB: double* ///outPos: double* ///outOrn: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3MultiplyTransforms")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, 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) ; @@ -3237,7 +3238,7 @@ public static extern void b3MultiplyTransforms(ref double posA, ref double ornA ///orn: double* ///outPos: double* ///outOrn: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InvertTransform")] + [System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InvertTransform")] public static extern void b3InvertTransform(ref double pos, ref double orn, ref double outPos, ref double outOrn) ; } diff --git a/examples/pybullet/unity3d/examples/NewBehaviourScript.cs b/examples/pybullet/unity3d/examples/NewBehaviourScript.cs index 42bcfddf0..44d64348c 100644 --- a/examples/pybullet/unity3d/examples/NewBehaviourScript.cs +++ b/examples/pybullet/unity3d/examples/NewBehaviourScript.cs @@ -10,78 +10,160 @@ using System; public class NewBehaviourScript : MonoBehaviour { - - - - [DllImport("TestCppPlug.dll")] - static extern int Add(int a, int b); - - [DllImport("TestCppPlug.dll")] - static extern int CallMe(Action action); - - [DllImport("TestCppPlug.dll")] - static extern IntPtr CreateSharedAPI(int id); - - [DllImport("TestCppPlug.dll")] - static extern int GetMyIdPlusTen(IntPtr api); - - [DllImport("TestCppPlug.dll")] - static extern void DeleteSharedAPI(IntPtr api); - - private void IWasCalled(int value) - { - text.text = value.ToString(); - } - + Text text; IntPtr sharedAPI; IntPtr pybullet; + int m_cubeUid; // Use this for initialization void Start () { text = GetComponent(); - CallMe(IWasCalled); - sharedAPI = CreateSharedAPI(30); - pybullet = NativeMethods.b3ConnectPhysicsDirect();// SharedMemory(12347); + + pybullet = NativeMethods.b3ConnectSharedMemory(NativeConstants.SHARED_MEMORY_KEY); + if (NativeMethods.b3CanSubmitCommand(pybullet)==0) + { + pybullet = NativeMethods.b3ConnectPhysicsDirect(); + } + + + IntPtr cmd = NativeMethods.b3InitResetSimulationCommand(pybullet); IntPtr status = NativeMethods.b3SubmitClientCommandAndWaitStatus(pybullet, cmd); + + { + IntPtr command = NativeMethods.b3InitPhysicsParamCommand(pybullet); + NativeMethods.b3PhysicsParamSetGravity(command, 0, -10, 0); + IntPtr statusHandle = NativeMethods.b3SubmitClientCommandAndWaitStatus(pybullet, command); + } + int numBodies = NativeMethods.b3GetNumBodies(pybullet); - cmd = NativeMethods.b3LoadUrdfCommandInit(pybullet, "plane.urdf"); + { + cmd = NativeMethods.b3LoadUrdfCommandInit(pybullet, "plane.urdf"); + Quaternion qq = Quaternion.Euler(-90, 0, 0); + NativeMethods.b3LoadUrdfCommandSetStartOrientation(cmd, qq.x, qq.y, qq.z, qq.w); + status = NativeMethods.b3SubmitClientCommandAndWaitStatus(pybullet, cmd); + } + + + cmd = NativeMethods.b3LoadUrdfCommandInit(pybullet, "cube.urdf"); + NativeMethods.b3LoadUrdfCommandSetStartPosition(cmd, 0, 20, 0); + Quaternion q = Quaternion.Euler(35, 0, 0); + NativeMethods.b3LoadUrdfCommandSetStartOrientation(cmd, q.x, q.y, q.z, q.w); status = NativeMethods.b3SubmitClientCommandAndWaitStatus(pybullet, cmd); + m_cubeUid = NativeMethods.b3GetStatusBodyIndex(status); + EnumSharedMemoryServerStatus statusType = (EnumSharedMemoryServerStatus)NativeMethods.b3GetStatusType(status); - if (statusType == EnumSharedMemoryServerStatus.CMD_URDF_LOADING_COMPLETED) + if (statusType == (EnumSharedMemoryServerStatus)EnumSharedMemoryServerStatus.CMD_URDF_LOADING_COMPLETED) { numBodies = NativeMethods.b3GetNumBodies(pybullet); text.text = numBodies.ToString(); + cmd = NativeMethods.b3InitRequestVisualShapeInformation(pybullet, m_cubeUid); + status = NativeMethods.b3SubmitClientCommandAndWaitStatus(pybullet, cmd); + statusType = (EnumSharedMemoryServerStatus) NativeMethods.b3GetStatusType(status); + + if (statusType == (EnumSharedMemoryServerStatus)EnumSharedMemoryServerStatus.CMD_VISUAL_SHAPE_INFO_COMPLETED) + { + b3VisualShapeInformation visuals = new b3VisualShapeInformation(); + NativeMethods.b3GetVisualShapeInformation(pybullet, ref visuals); + System.Console.WriteLine("visuals.m_numVisualShapes=" + visuals.m_numVisualShapes); + System.IntPtr visualPtr = visuals.m_visualShapeData; + + for (int s = 0; s < visuals.m_numVisualShapes; s++) + { + b3VisualShapeData visual = (b3VisualShapeData)Marshal.PtrToStructure(visualPtr, typeof(b3VisualShapeData)); + visualPtr = new IntPtr(visualPtr.ToInt64()+(Marshal.SizeOf(typeof(b3VisualShapeData)))); + double x = visual.m_dimensions[0]; + double y = visual.m_dimensions[1]; + double z = visual.m_dimensions[2]; + System.Console.WriteLine("visual.m_visualGeometryType = " + visual.m_visualGeometryType); + System.Console.WriteLine("visual.m_dimensions" + x + "," + y + "," + z); + if (visual.m_visualGeometryType == (int)eUrdfGeomTypes.GEOM_MESH) + { + System.Console.WriteLine("visual.m_meshAssetFileName=" + visual.m_meshAssetFileName); + text.text = visual.m_meshAssetFileName; + } + } + } if (numBodies > 0) { - //b3BodyInfo info=new b3BodyInfo(); - //NativeMethods.b3GetBodyInfo(pybullet, 0, ref info ); - //text.text = info.m_baseName; + b3BodyInfo info=new b3BodyInfo(); + NativeMethods.b3GetBodyInfo(pybullet, 0, ref info ); + + text.text = info.m_baseName; } + + } - //IntPtr clientPtr = b3CreateInProcessPhysicsServerAndConnect(0, ref ptr); } - + public struct MyPos + { + public double x, y, z; + public double qx, qy, qz, qw; + } // Update is called once per frame void Update () { - //if (pybullet != IntPtr.Zero) + if (pybullet != IntPtr.Zero) { IntPtr cmd = NativeMethods.b3InitStepSimulationCommand(pybullet); IntPtr status = NativeMethods.b3SubmitClientCommandAndWaitStatus(pybullet, cmd); - - //text.text = System.IO.Directory.GetCurrentDirectory().ToString(); - //text.text = Add(4, 5).ToString(); - //text.text = UnityEngine.Random.Range(0f, 1f).ToString();// GetMyIdPlusTen(sharedAPI).ToString(); } + if (m_cubeUid>=0) + { + IntPtr cmd_handle = + NativeMethods.b3RequestActualStateCommandInit(pybullet, m_cubeUid); + IntPtr status_handle = NativeMethods.b3SubmitClientCommandAndWaitStatus(pybullet, cmd_handle); + + EnumSharedMemoryServerStatus status_type = (EnumSharedMemoryServerStatus)NativeMethods.b3GetStatusType(status_handle); + + if (status_type == EnumSharedMemoryServerStatus.CMD_ACTUAL_STATE_UPDATE_COMPLETED) + { + IntPtr p = IntPtr.Zero; + int objUid = 0; + int numDofQ = 0; + int numDofU = 0; + IntPtr inertialFrame = IntPtr.Zero; + IntPtr actualStateQ = IntPtr.Zero; + IntPtr actualStateQdot = IntPtr.Zero; + IntPtr joint_reaction_forces = IntPtr.Zero; + + NativeMethods.b3GetStatusActualState( + status_handle, ref objUid, ref numDofQ , ref numDofU, + ref inertialFrame, ref actualStateQ, + ref actualStateQdot , ref joint_reaction_forces); + //Debug.Log("objUid=" + objUid.ToString()); + //Debug.Log("numDofQ=" + numDofQ.ToString()); + //Debug.Log("numDofU=" + numDofU.ToString()); + + MyPos mpos = (MyPos)Marshal.PtrToStructure(actualStateQ, typeof(MyPos)); + //Debug.Log("pos=(" + mpos.x.ToString()+","+ mpos.y.ToString()+ "," + mpos.z.ToString()+")"); + //Debug.Log("orn=(" + mpos.qx.ToString() + "," + mpos.qy.ToString() + "," + mpos.qz.ToString() + mpos.qw.ToString() + ")"); + Vector3 pos = new Vector3((float)mpos.x, (float)mpos.y, (float)mpos.z); + Quaternion orn = new Quaternion((float)mpos.qx, (float)mpos.qy, (float)mpos.qz, (float)mpos.qw); + Vector3 dimensions = new Vector3(1, 1, 1); + CjLib.DebugUtil.DrawBox(pos, orn, dimensions, Color.black); + } + + + } + + { + CjLib.DebugUtil.DrawLine(new Vector3(-1, 0, 0), new Vector3(1, 0, 0), Color.red); + CjLib.DebugUtil.DrawLine(new Vector3(0, -1, 0), new Vector3(0, 1, 0), Color.green); + CjLib.DebugUtil.DrawLine(new Vector3(0, 0, -1), new Vector3(0, 0, 1), Color.blue); + } + } void OnDestroy() { - NativeMethods.b3DisconnectSharedMemory(pybullet); + if (pybullet != IntPtr.Zero) + { + NativeMethods.b3DisconnectSharedMemory(pybullet); + } } } diff --git a/examples/pybullet/unity3d/examples/NewBehaviourScript.cs.meta b/examples/pybullet/unity3d/examples/NewBehaviourScript.cs.meta deleted file mode 100644 index 6e595b031..000000000 --- a/examples/pybullet/unity3d/examples/NewBehaviourScript.cs.meta +++ /dev/null @@ -1,12 +0,0 @@ -fileFormatVersion: 2 -guid: 6197b3a0389e92c47b7d8698e5f61f06 -timeCreated: 1505961790 -licenseType: Free -MonoImporter: - serializedVersion: 2 - defaultReferences: [] - executionOrder: 0 - icon: {instanceID: 0} - userData: - assetBundleName: - assetBundleVariant: diff --git a/test/GwenOpenGLTest/OpenGLSample.cpp b/test/GwenOpenGLTest/OpenGLSample.cpp index 89a4d908c..95c77b55b 100644 --- a/test/GwenOpenGLTest/OpenGLSample.cpp +++ b/test/GwenOpenGLTest/OpenGLSample.cpp @@ -331,7 +331,7 @@ int main() int majorGlVersion, minorGlVersion; - if (!sscanf((const char*)glGetString(GL_VERSION), "%d.%d", &majorGlVersion, &minorGlVersion)==2) + if (!(sscanf((const char*)glGetString(GL_VERSION), "%d.%d", &majorGlVersion, &minorGlVersion)==2)) { printf("Exit: Error cannot extract OpenGL version from GL_VERSION string\n"); exit(0); diff --git a/test/enet/chat/server/main.cpp b/test/enet/chat/server/main.cpp index ed708131b..d1f85bd99 100644 --- a/test/enet/chat/server/main.cpp +++ b/test/enet/chat/server/main.cpp @@ -64,7 +64,7 @@ int main(int argc, char *argv[]) break; case ENET_EVENT_TYPE_RECEIVE: - printf("A packet of length %u containing '%s' was " + printf("A packet of length %lu containing '%s' was " "received from %s on channel %u.\n", event.packet->dataLength, event.packet->data, @@ -83,6 +83,8 @@ int main(int argc, char *argv[]) event.peer->data = NULL; + break; + case ENET_EVENT_TYPE_NONE: break; } }