diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index 46c4ae0be..9bc362373 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -9,7 +9,7 @@ #include "SharedMemoryCommands.h" -b3SharedMemoryCommandHandle b3LoadSdfCommandInit(b3PhysicsClientHandle physClient, const char* sdfFileName) +B3_SHARED_API b3SharedMemoryCommandHandle b3LoadSdfCommandInit(b3PhysicsClientHandle physClient, const char* sdfFileName) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -31,7 +31,7 @@ b3SharedMemoryCommandHandle b3LoadSdfCommandInit(b3PhysicsClientHandle physClien return (b3SharedMemoryCommandHandle) command; } -b3SharedMemoryCommandHandle b3SaveWorldCommandInit(b3PhysicsClientHandle physClient, const char* sdfFileName) +B3_SHARED_API b3SharedMemoryCommandHandle b3SaveWorldCommandInit(b3PhysicsClientHandle physClient, const char* sdfFileName) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -53,7 +53,7 @@ b3SharedMemoryCommandHandle b3SaveWorldCommandInit(b3PhysicsClientHandle physCli return (b3SharedMemoryCommandHandle) command; } -b3SharedMemoryCommandHandle b3LoadUrdfCommandInit(b3PhysicsClientHandle physClient, const char* urdfFileName) +B3_SHARED_API b3SharedMemoryCommandHandle b3LoadUrdfCommandInit(b3PhysicsClientHandle physClient, const char* urdfFileName) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -80,7 +80,7 @@ b3SharedMemoryCommandHandle b3LoadUrdfCommandInit(b3PhysicsClientHandle physClie return 0; } -b3SharedMemoryCommandHandle b3LoadBulletCommandInit(b3PhysicsClientHandle physClient, const char* fileName) +B3_SHARED_API b3SharedMemoryCommandHandle b3LoadBulletCommandInit(b3PhysicsClientHandle physClient, const char* fileName) { PhysicsClient* cl = (PhysicsClient*)physClient; b3Assert(cl); @@ -107,7 +107,7 @@ b3SharedMemoryCommandHandle b3LoadBulletCommandInit(b3PhysicsClientHandle physCl return 0; } -b3SharedMemoryCommandHandle b3SaveBulletCommandInit(b3PhysicsClientHandle physClient, const char* fileName) +B3_SHARED_API b3SharedMemoryCommandHandle b3SaveBulletCommandInit(b3PhysicsClientHandle physClient, const char* fileName) { PhysicsClient* cl = (PhysicsClient*)physClient; b3Assert(cl); @@ -133,7 +133,7 @@ b3SharedMemoryCommandHandle b3SaveBulletCommandInit(b3PhysicsClientHandle physCl } return 0; } -b3SharedMemoryCommandHandle b3LoadMJCFCommandInit(b3PhysicsClientHandle physClient, const char* fileName) +B3_SHARED_API b3SharedMemoryCommandHandle b3LoadMJCFCommandInit(b3PhysicsClientHandle physClient, const char* fileName) { PhysicsClient* cl = (PhysicsClient*)physClient; b3Assert(cl); @@ -160,7 +160,7 @@ b3SharedMemoryCommandHandle b3LoadMJCFCommandInit(b3PhysicsClientHandle physClie return 0; } -void b3LoadMJCFCommandSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags) +B3_SHARED_API void b3LoadMJCFCommandSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_LOAD_MJCF); @@ -171,7 +171,7 @@ void b3LoadMJCFCommandSetFlags(b3SharedMemoryCommandHandle commandHandle, int fl } } -b3SharedMemoryCommandHandle b3LoadBunnyCommandInit(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryCommandHandle b3LoadBunnyCommandInit(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -185,7 +185,7 @@ b3SharedMemoryCommandHandle b3LoadBunnyCommandInit(b3PhysicsClientHandle physCli return (b3SharedMemoryCommandHandle) command; } -int b3LoadBunnySetScale(b3SharedMemoryCommandHandle commandHandle, double scale) +B3_SHARED_API int b3LoadBunnySetScale(b3SharedMemoryCommandHandle commandHandle, double scale) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_LOAD_BUNNY); @@ -194,7 +194,7 @@ int b3LoadBunnySetScale(b3SharedMemoryCommandHandle commandHandle, double scale) return 0; } -int b3LoadBunnySetMass(b3SharedMemoryCommandHandle commandHandle, double mass) +B3_SHARED_API int b3LoadBunnySetMass(b3SharedMemoryCommandHandle commandHandle, double mass) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_LOAD_BUNNY); @@ -203,7 +203,7 @@ int b3LoadBunnySetMass(b3SharedMemoryCommandHandle commandHandle, double mass) return 0; } -int b3LoadBunnySetCollisionMargin(b3SharedMemoryCommandHandle commandHandle, double collisionMargin) +B3_SHARED_API int b3LoadBunnySetCollisionMargin(b3SharedMemoryCommandHandle commandHandle, double collisionMargin) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_LOAD_BUNNY); @@ -212,7 +212,7 @@ int b3LoadBunnySetCollisionMargin(b3SharedMemoryCommandHandle commandHandle, dou return 0; } -int b3LoadUrdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody) +B3_SHARED_API int b3LoadUrdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -223,7 +223,7 @@ int b3LoadUrdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, return 0; } -int b3LoadUrdfCommandSetGlobalScaling(b3SharedMemoryCommandHandle commandHandle, double globalScaling) +B3_SHARED_API int b3LoadUrdfCommandSetGlobalScaling(b3SharedMemoryCommandHandle commandHandle, double globalScaling) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -235,7 +235,7 @@ int b3LoadUrdfCommandSetGlobalScaling(b3SharedMemoryCommandHandle commandHandle, -int b3LoadSdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody) +B3_SHARED_API int b3LoadSdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -246,7 +246,7 @@ int b3LoadSdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, i return 0; } -int b3LoadSdfCommandSetUseGlobalScaling(b3SharedMemoryCommandHandle commandHandle, double globalScaling) +B3_SHARED_API int b3LoadSdfCommandSetUseGlobalScaling(b3SharedMemoryCommandHandle commandHandle, double globalScaling) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -259,7 +259,7 @@ int b3LoadSdfCommandSetUseGlobalScaling(b3SharedMemoryCommandHandle commandHandl -int b3LoadUrdfCommandSetUseFixedBase(b3SharedMemoryCommandHandle commandHandle, int useFixedBase) +B3_SHARED_API int b3LoadUrdfCommandSetUseFixedBase(b3SharedMemoryCommandHandle commandHandle, int useFixedBase) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -273,7 +273,7 @@ int b3LoadUrdfCommandSetUseFixedBase(b3SharedMemoryCommandHandle commandHandle, return -1; } -int b3LoadUrdfCommandSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags) +B3_SHARED_API int b3LoadUrdfCommandSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -286,7 +286,7 @@ int b3LoadUrdfCommandSetFlags(b3SharedMemoryCommandHandle commandHandle, int fla return 0; } -int b3LoadUrdfCommandSetStartPosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ) +B3_SHARED_API int b3LoadUrdfCommandSetStartPosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -305,7 +305,7 @@ int b3LoadUrdfCommandSetStartPosition(b3SharedMemoryCommandHandle commandHandle, return -1; } -int b3LoadUrdfCommandSetStartOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW) +B3_SHARED_API int b3LoadUrdfCommandSetStartOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -325,7 +325,7 @@ int b3LoadUrdfCommandSetStartOrientation(b3SharedMemoryCommandHandle commandHand return -1; } -b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -337,7 +337,7 @@ b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle return (b3SharedMemoryCommandHandle) command; } -int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, double gravx,double gravy, double gravz) +B3_SHARED_API int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, double gravx,double gravy, double gravz) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS); @@ -348,7 +348,7 @@ int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, doub return 0; } -int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandHandle commandHandle, int enableRealTimeSimulation) +B3_SHARED_API int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandHandle commandHandle, int enableRealTimeSimulation) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS); @@ -357,7 +357,7 @@ int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandHandle commandH return 0; } -int b3PhysicsParamSetInternalSimFlags(b3SharedMemoryCommandHandle commandHandle, int flags) +B3_SHARED_API int b3PhysicsParamSetInternalSimFlags(b3SharedMemoryCommandHandle commandHandle, int flags) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS); @@ -366,7 +366,7 @@ int b3PhysicsParamSetInternalSimFlags(b3SharedMemoryCommandHandle commandHan return 0; } -int b3PhysicsParamSetUseSplitImpulse(b3SharedMemoryCommandHandle commandHandle, int useSplitImpulse) +B3_SHARED_API int b3PhysicsParamSetUseSplitImpulse(b3SharedMemoryCommandHandle commandHandle, int useSplitImpulse) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS); @@ -376,7 +376,7 @@ int b3PhysicsParamSetUseSplitImpulse(b3SharedMemoryCommandHandle commandHandle, return 0; } -int b3PhysicsParamSetSplitImpulsePenetrationThreshold(b3SharedMemoryCommandHandle commandHandle, double splitImpulsePenetrationThreshold) +B3_SHARED_API int b3PhysicsParamSetSplitImpulsePenetrationThreshold(b3SharedMemoryCommandHandle commandHandle, double splitImpulsePenetrationThreshold) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS); @@ -386,7 +386,7 @@ int b3PhysicsParamSetSplitImpulsePenetrationThreshold(b3SharedMemoryCommandHandl return 0; } -int b3PhysicsParamSetContactBreakingThreshold(b3SharedMemoryCommandHandle commandHandle, double contactBreakingThreshold) +B3_SHARED_API int b3PhysicsParamSetContactBreakingThreshold(b3SharedMemoryCommandHandle commandHandle, double contactBreakingThreshold) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS); @@ -395,7 +395,7 @@ int b3PhysicsParamSetContactBreakingThreshold(b3SharedMemoryCommandHandle comman command->m_updateFlags |= SIM_PARAM_UPDATE_CONTACT_BREAKING_THRESHOLD; return 0; } -int b3PhysicsParamSetMaxNumCommandsPer1ms(b3SharedMemoryCommandHandle commandHandle, int maxNumCmdPer1ms) +B3_SHARED_API int b3PhysicsParamSetMaxNumCommandsPer1ms(b3SharedMemoryCommandHandle commandHandle, int maxNumCmdPer1ms) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS); @@ -406,7 +406,7 @@ int b3PhysicsParamSetMaxNumCommandsPer1ms(b3SharedMemoryCommandHandle commandHan } -int b3PhysicsParamSetEnableFileCaching(b3SharedMemoryCommandHandle commandHandle, int enableFileCaching) +B3_SHARED_API int b3PhysicsParamSetEnableFileCaching(b3SharedMemoryCommandHandle commandHandle, int enableFileCaching) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS); @@ -417,7 +417,7 @@ int b3PhysicsParamSetEnableFileCaching(b3SharedMemoryCommandHandle commandHandle } -int b3PhysicsParamSetRestitutionVelocityThreshold(b3SharedMemoryCommandHandle commandHandle, double restitutionVelocityThreshold) +B3_SHARED_API int b3PhysicsParamSetRestitutionVelocityThreshold(b3SharedMemoryCommandHandle commandHandle, double restitutionVelocityThreshold) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS); @@ -429,7 +429,7 @@ int b3PhysicsParamSetRestitutionVelocityThreshold(b3SharedMemoryCommandHandle co } -int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHandle, int numSolverIterations) +B3_SHARED_API int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHandle, int numSolverIterations) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS); @@ -439,7 +439,7 @@ int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHand } -int b3PhysicsParamSetCollisionFilterMode(b3SharedMemoryCommandHandle commandHandle, int filterMode) +B3_SHARED_API int b3PhysicsParamSetCollisionFilterMode(b3SharedMemoryCommandHandle commandHandle, int filterMode) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS); @@ -450,7 +450,7 @@ int b3PhysicsParamSetCollisionFilterMode(b3SharedMemoryCommandHandle commandHand -int b3PhysicsParamSetTimeStep(b3SharedMemoryCommandHandle commandHandle, double timeStep) +B3_SHARED_API int b3PhysicsParamSetTimeStep(b3SharedMemoryCommandHandle commandHandle, double timeStep) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS); @@ -459,7 +459,7 @@ int b3PhysicsParamSetTimeStep(b3SharedMemoryCommandHandle commandHandle, double return 0; } -int b3PhysicsParamSetNumSubSteps(b3SharedMemoryCommandHandle commandHandle, int numSubSteps) +B3_SHARED_API int b3PhysicsParamSetNumSubSteps(b3SharedMemoryCommandHandle commandHandle, int numSubSteps) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS); @@ -469,7 +469,7 @@ int b3PhysicsParamSetNumSubSteps(b3SharedMemoryCommandHandle commandHandle, int } -int b3PhysicsParamSetDefaultContactERP(b3SharedMemoryCommandHandle commandHandle, double defaultContactERP) +B3_SHARED_API int b3PhysicsParamSetDefaultContactERP(b3SharedMemoryCommandHandle commandHandle, double defaultContactERP) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS); @@ -477,7 +477,7 @@ int b3PhysicsParamSetDefaultContactERP(b3SharedMemoryCommandHandle commandHandle command->m_physSimParamArgs.m_defaultContactERP = defaultContactERP; return 0; } -int b3PhysicsParamSetDefaultNonContactERP(b3SharedMemoryCommandHandle commandHandle, double defaultNonContactERP) +B3_SHARED_API int b3PhysicsParamSetDefaultNonContactERP(b3SharedMemoryCommandHandle commandHandle, double defaultNonContactERP) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS); @@ -485,7 +485,7 @@ int b3PhysicsParamSetDefaultNonContactERP(b3SharedMemoryCommandHandle commandHan command->m_physSimParamArgs.m_defaultNonContactERP = defaultNonContactERP; return 0; } -int b3PhysicsParamSetDefaultFrictionERP(b3SharedMemoryCommandHandle commandHandle, double frictionERP) +B3_SHARED_API int b3PhysicsParamSetDefaultFrictionERP(b3SharedMemoryCommandHandle commandHandle, double frictionERP) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS); @@ -495,7 +495,7 @@ int b3PhysicsParamSetDefaultFrictionERP(b3SharedMemoryCommandHandle commandHandl } -b3SharedMemoryCommandHandle b3InitStepSimulationCommand(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitStepSimulationCommand(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -507,7 +507,7 @@ b3SharedMemoryCommandHandle b3InitStepSimulationCommand(b3PhysicsClientHandle ph return (b3SharedMemoryCommandHandle) command; } -b3SharedMemoryCommandHandle b3InitResetSimulationCommand(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitResetSimulationCommand(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -522,12 +522,12 @@ b3SharedMemoryCommandHandle b3InitResetSimulationCommand(b3PhysicsClientHand } -b3SharedMemoryCommandHandle b3JointControlCommandInit(b3PhysicsClientHandle physClient, int controlMode) +B3_SHARED_API b3SharedMemoryCommandHandle b3JointControlCommandInit(b3PhysicsClientHandle physClient, int controlMode) { return b3JointControlCommandInit2(physClient,0,controlMode); } -b3SharedMemoryCommandHandle b3JointControlCommandInit2( b3PhysicsClientHandle physClient, int bodyUniqueId, int controlMode) +B3_SHARED_API b3SharedMemoryCommandHandle b3JointControlCommandInit2( b3PhysicsClientHandle physClient, int bodyUniqueId, int controlMode) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -545,7 +545,7 @@ b3SharedMemoryCommandHandle b3JointControlCommandInit2( b3PhysicsClientHandle ph return (b3SharedMemoryCommandHandle) command; } -int b3JointControlSetDesiredPosition(b3SharedMemoryCommandHandle commandHandle, int qIndex, double value) +B3_SHARED_API int b3JointControlSetDesiredPosition(b3SharedMemoryCommandHandle commandHandle, int qIndex, double value) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -558,7 +558,7 @@ int b3JointControlSetDesiredPosition(b3SharedMemoryCommandHandle commandHandle, return 0; } -int b3JointControlSetKp(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value) +B3_SHARED_API int b3JointControlSetKp(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -571,7 +571,7 @@ int b3JointControlSetKp(b3SharedMemoryCommandHandle commandHandle, int dofIndex, return 0; } -int b3JointControlSetKd(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value) +B3_SHARED_API int b3JointControlSetKd(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -584,7 +584,7 @@ int b3JointControlSetKd(b3SharedMemoryCommandHandle commandHandle, int dofIndex, return 0; } -int b3JointControlSetDesiredVelocity(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value) +B3_SHARED_API int b3JointControlSetDesiredVelocity(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -598,7 +598,7 @@ int b3JointControlSetDesiredVelocity(b3SharedMemoryCommandHandle commandHandle, } -int b3JointControlSetMaximumForce(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value) +B3_SHARED_API int b3JointControlSetMaximumForce(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -611,7 +611,7 @@ int b3JointControlSetMaximumForce(b3SharedMemoryCommandHandle commandHandle, int return 0; } -int b3JointControlSetDesiredForceTorque(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value) +B3_SHARED_API int b3JointControlSetDesiredForceTorque(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -624,7 +624,7 @@ int b3JointControlSetDesiredForceTorque(b3SharedMemoryCommandHandle commandHandl return 0; } -b3SharedMemoryCommandHandle b3RequestActualStateCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId) +B3_SHARED_API b3SharedMemoryCommandHandle b3RequestActualStateCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -637,7 +637,7 @@ b3SharedMemoryCommandHandle b3RequestActualStateCommandInit(b3PhysicsClientHandl return (b3SharedMemoryCommandHandle) command; } -int b3RequestActualStateCommandComputeLinkVelocity(b3SharedMemoryCommandHandle commandHandle, int computeLinkVelocity) +B3_SHARED_API int b3RequestActualStateCommandComputeLinkVelocity(b3SharedMemoryCommandHandle commandHandle, int computeLinkVelocity) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -650,7 +650,7 @@ int b3RequestActualStateCommandComputeLinkVelocity(b3SharedMemoryCommandHandle c } -int b3GetJointState(b3PhysicsClientHandle physClient, b3SharedMemoryStatusHandle statusHandle, int jointIndex, b3JointSensorState *state) +B3_SHARED_API int b3GetJointState(b3PhysicsClientHandle physClient, b3SharedMemoryStatusHandle statusHandle, int jointIndex, b3JointSensorState *state) { const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle; b3Assert(status); @@ -683,7 +683,7 @@ int b3GetJointState(b3PhysicsClientHandle physClient, b3SharedMemoryStatusHandle return 0; } -int b3GetLinkState(b3PhysicsClientHandle physClient, b3SharedMemoryStatusHandle statusHandle, int linkIndex, b3LinkState *state) +B3_SHARED_API int b3GetLinkState(b3PhysicsClientHandle physClient, b3SharedMemoryStatusHandle statusHandle, int linkIndex, b3LinkState *state) { const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle; b3Assert(status); @@ -730,7 +730,7 @@ int b3GetLinkState(b3PhysicsClientHandle physClient, b3SharedMemoryStatusHandle return 0; } -b3SharedMemoryCommandHandle b3CreateCollisionShapeCommandInit(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryCommandHandle b3CreateCollisionShapeCommandInit(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -747,7 +747,7 @@ b3SharedMemoryCommandHandle b3CreateCollisionShapeCommandInit(b3PhysicsClientHan return 0; } -int b3CreateCollisionShapeAddSphere(b3SharedMemoryCommandHandle commandHandle,double radius) +B3_SHARED_API int b3CreateCollisionShapeAddSphere(b3SharedMemoryCommandHandle commandHandle,double radius) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -768,7 +768,7 @@ int b3CreateCollisionShapeAddSphere(b3SharedMemoryCommandHandle commandHandle,do return -1; } -int b3CreateCollisionShapeAddBox(b3SharedMemoryCommandHandle commandHandle,double halfExtents[3]) +B3_SHARED_API int b3CreateCollisionShapeAddBox(b3SharedMemoryCommandHandle commandHandle,double halfExtents[3]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -791,7 +791,7 @@ int b3CreateCollisionShapeAddBox(b3SharedMemoryCommandHandle commandHandle,doubl return -1; } -int b3CreateCollisionShapeAddCapsule(b3SharedMemoryCommandHandle commandHandle,double radius, double height) +B3_SHARED_API int b3CreateCollisionShapeAddCapsule(b3SharedMemoryCommandHandle commandHandle,double radius, double height) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -813,7 +813,7 @@ int b3CreateCollisionShapeAddCapsule(b3SharedMemoryCommandHandle commandHandle,d return -1; } -int b3CreateCollisionShapeAddCylinder(b3SharedMemoryCommandHandle commandHandle,double radius, double height) +B3_SHARED_API int b3CreateCollisionShapeAddCylinder(b3SharedMemoryCommandHandle commandHandle,double radius, double height) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -836,7 +836,7 @@ int b3CreateCollisionShapeAddCylinder(b3SharedMemoryCommandHandle commandHandle, } -int b3CreateCollisionShapeAddPlane(b3SharedMemoryCommandHandle commandHandle, double planeNormal[3], double planeConstant) +B3_SHARED_API int b3CreateCollisionShapeAddPlane(b3SharedMemoryCommandHandle commandHandle, double planeNormal[3], double planeConstant) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -860,7 +860,7 @@ int b3CreateCollisionShapeAddPlane(b3SharedMemoryCommandHandle commandHandle, do return -1; } -int b3CreateCollisionShapeAddMesh(b3SharedMemoryCommandHandle commandHandle,const char* fileName, double meshScale[3]) +B3_SHARED_API int b3CreateCollisionShapeAddMesh(b3SharedMemoryCommandHandle commandHandle,const char* fileName, double meshScale[3]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -885,7 +885,7 @@ int b3CreateCollisionShapeAddMesh(b3SharedMemoryCommandHandle commandHandle,cons return -1; } -void b3CreateCollisionSetFlag(b3SharedMemoryCommandHandle commandHandle,int shapeIndex, int flags) +B3_SHARED_API void b3CreateCollisionSetFlag(b3SharedMemoryCommandHandle commandHandle,int shapeIndex, int flags) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; @@ -901,7 +901,7 @@ void b3CreateCollisionSetFlag(b3SharedMemoryCommandHandle commandHandle,int shap } -void b3CreateCollisionShapeSetChildTransform(b3SharedMemoryCommandHandle commandHandle,int shapeIndex, double childPosition[3], double childOrientation[4]) +B3_SHARED_API void b3CreateCollisionShapeSetChildTransform(b3SharedMemoryCommandHandle commandHandle,int shapeIndex, double childPosition[3], double childOrientation[4]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -923,7 +923,7 @@ void b3CreateCollisionShapeSetChildTransform(b3SharedMemoryCommandHandle command } -int b3GetStatusCollisionShapeUniqueId(b3SharedMemoryStatusHandle statusHandle) +B3_SHARED_API int b3GetStatusCollisionShapeUniqueId(b3SharedMemoryStatusHandle statusHandle) { const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle; b3Assert(status); @@ -936,7 +936,7 @@ int b3GetStatusCollisionShapeUniqueId(b3SharedMemoryStatusHandle statusHandle) } -b3SharedMemoryCommandHandle b3CreateVisualShapeCommandInit(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryCommandHandle b3CreateVisualShapeCommandInit(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -952,7 +952,7 @@ b3SharedMemoryCommandHandle b3CreateVisualShapeCommandInit(b3PhysicsClientHandle return 0; } -int b3GetStatusVisualShapeUniqueId(b3SharedMemoryStatusHandle statusHandle) +B3_SHARED_API int b3GetStatusVisualShapeUniqueId(b3SharedMemoryStatusHandle statusHandle) { const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle; b3Assert(status); @@ -964,7 +964,7 @@ int b3GetStatusVisualShapeUniqueId(b3SharedMemoryStatusHandle statusHandle) return -1; } -b3SharedMemoryCommandHandle b3CreateMultiBodyCommandInit(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryCommandHandle b3CreateMultiBodyCommandInit(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -983,7 +983,7 @@ b3SharedMemoryCommandHandle b3CreateMultiBodyCommandInit(b3PhysicsClientHandle p return 0; } -int b3CreateMultiBodyBase(b3SharedMemoryCommandHandle commandHandle, double mass, int collisionShapeUnique, int visualShapeUniqueId, double basePosition[3], double baseOrientation[4] , double baseInertialFramePosition[3], double baseInertialFrameOrientation[4]) +B3_SHARED_API int b3CreateMultiBodyBase(b3SharedMemoryCommandHandle commandHandle, double mass, int collisionShapeUnique, int visualShapeUniqueId, double basePosition[3], double baseOrientation[4] , double baseInertialFramePosition[3], double baseInertialFrameOrientation[4]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -1036,7 +1036,7 @@ int b3CreateMultiBodyBase(b3SharedMemoryCommandHandle commandHandle, double mass return -2; } -int b3CreateMultiBodyLink(b3SharedMemoryCommandHandle commandHandle, double linkMass, double linkCollisionShapeIndex, +B3_SHARED_API int b3CreateMultiBodyLink(b3SharedMemoryCommandHandle commandHandle, double linkMass, double linkCollisionShapeIndex, double linkVisualShapeIndex, double linkPosition[3], double linkOrientation[4], @@ -1102,7 +1102,7 @@ int b3CreateMultiBodyLink(b3SharedMemoryCommandHandle commandHandle, double link //useMaximalCoordinates are disabled by default, enabling them is experimental and not fully supported yet -void b3CreateMultiBodyUseMaximalCoordinates(b3SharedMemoryCommandHandle commandHandle) +B3_SHARED_API void b3CreateMultiBodyUseMaximalCoordinates(b3SharedMemoryCommandHandle commandHandle) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -1113,7 +1113,7 @@ void b3CreateMultiBodyUseMaximalCoordinates(b3SharedMemoryCommandHandle commandH } } -int b3GetStatusMultiBodyUniqueId(b3SharedMemoryStatusHandle statusHandle) +B3_SHARED_API int b3GetStatusMultiBodyUniqueId(b3SharedMemoryStatusHandle statusHandle) { const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle; b3Assert(status); @@ -1125,7 +1125,7 @@ int b3GetStatusMultiBodyUniqueId(b3SharedMemoryStatusHandle statusHandle) return -1; } -b3SharedMemoryCommandHandle b3CreateBoxShapeCommandInit(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryCommandHandle b3CreateBoxShapeCommandInit(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -1137,7 +1137,7 @@ b3SharedMemoryCommandHandle b3CreateBoxShapeCommandInit(b3PhysicsClientHandle ph return (b3SharedMemoryCommandHandle) command; } -int b3CreateBoxCommandSetStartPosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ) +B3_SHARED_API int b3CreateBoxCommandSetStartPosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -1151,7 +1151,7 @@ int b3CreateBoxCommandSetStartPosition(b3SharedMemoryCommandHandle commandHandle } -int b3CreateBoxCommandSetHalfExtents(b3SharedMemoryCommandHandle commandHandle, double halfExtentsX,double halfExtentsY,double halfExtentsZ) +B3_SHARED_API int b3CreateBoxCommandSetHalfExtents(b3SharedMemoryCommandHandle commandHandle, double halfExtentsX,double halfExtentsY,double halfExtentsZ) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -1166,7 +1166,7 @@ int b3CreateBoxCommandSetHalfExtents(b3SharedMemoryCommandHandle commandHandle, } -int b3CreateBoxCommandSetMass(b3SharedMemoryCommandHandle commandHandle, double mass) +B3_SHARED_API int b3CreateBoxCommandSetMass(b3SharedMemoryCommandHandle commandHandle, double mass) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -1177,7 +1177,7 @@ int b3CreateBoxCommandSetMass(b3SharedMemoryCommandHandle commandHandle, double } -int b3CreateBoxCommandSetCollisionShapeType(b3SharedMemoryCommandHandle commandHandle, int collisionShapeType) +B3_SHARED_API int b3CreateBoxCommandSetCollisionShapeType(b3SharedMemoryCommandHandle commandHandle, int collisionShapeType) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -1188,7 +1188,7 @@ int b3CreateBoxCommandSetCollisionShapeType(b3SharedMemoryCommandHandle commandH return 0; } -int b3CreateBoxCommandSetColorRGBA(b3SharedMemoryCommandHandle commandHandle, double red,double green,double blue, double alpha) +B3_SHARED_API int b3CreateBoxCommandSetColorRGBA(b3SharedMemoryCommandHandle commandHandle, double red,double green,double blue, double alpha) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -1201,7 +1201,7 @@ int b3CreateBoxCommandSetColorRGBA(b3SharedMemoryCommandHandle commandHandle, do return 0; } -int b3CreateBoxCommandSetStartOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW) +B3_SHARED_API int b3CreateBoxCommandSetStartOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -1215,7 +1215,7 @@ int b3CreateBoxCommandSetStartOrientation(b3SharedMemoryCommandHandle commandHan return 0; } -b3SharedMemoryCommandHandle b3CreatePoseCommandInit(b3PhysicsClientHandle physClient, int bodyIndex) +B3_SHARED_API b3SharedMemoryCommandHandle b3CreatePoseCommandInit(b3PhysicsClientHandle physClient, int bodyIndex) { PhysicsClient* cl = (PhysicsClient* ) physClient; @@ -1235,7 +1235,7 @@ b3SharedMemoryCommandHandle b3CreatePoseCommandInit(b3PhysicsClientHandle physCl return (b3SharedMemoryCommandHandle) command; } -int b3CreatePoseCommandSetBasePosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ) +B3_SHARED_API int b3CreatePoseCommandSetBasePosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -1252,7 +1252,7 @@ int b3CreatePoseCommandSetBasePosition(b3SharedMemoryCommandHandle commandHandle return 0; } -int b3CreatePoseCommandSetBaseOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW) +B3_SHARED_API int b3CreatePoseCommandSetBaseOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -1271,7 +1271,7 @@ int b3CreatePoseCommandSetBaseOrientation(b3SharedMemoryCommandHandle commandHan return 0; } -int b3CreatePoseCommandSetBaseLinearVelocity(b3SharedMemoryCommandHandle commandHandle, double linVel[3]) +B3_SHARED_API int b3CreatePoseCommandSetBaseLinearVelocity(b3SharedMemoryCommandHandle commandHandle, double linVel[3]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -1288,7 +1288,7 @@ int b3CreatePoseCommandSetBaseLinearVelocity(b3SharedMemoryCommandHandle command return 0; } -int b3CreatePoseCommandSetBaseAngularVelocity(b3SharedMemoryCommandHandle commandHandle, double angVel[3]) +B3_SHARED_API int b3CreatePoseCommandSetBaseAngularVelocity(b3SharedMemoryCommandHandle commandHandle, double angVel[3]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -1305,7 +1305,7 @@ int b3CreatePoseCommandSetBaseAngularVelocity(b3SharedMemoryCommandHandle comman return 0; } -int b3CreatePoseCommandSetJointPositions(b3SharedMemoryCommandHandle commandHandle, int numJointPositions, const double* jointPositions) +B3_SHARED_API int b3CreatePoseCommandSetJointPositions(b3SharedMemoryCommandHandle commandHandle, int numJointPositions, const double* jointPositions) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -1324,7 +1324,7 @@ int b3CreatePoseCommandSetJointPositions(b3SharedMemoryCommandHandle commandHand -int b3CreatePoseCommandSetJointPosition(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, int jointIndex, double jointPosition) +B3_SHARED_API int b3CreatePoseCommandSetJointPosition(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, int jointIndex, double jointPosition) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -1341,7 +1341,7 @@ int b3CreatePoseCommandSetJointPosition(b3PhysicsClientHandle physClient, b3Shar return 0; } -int b3CreatePoseCommandSetJointVelocities(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, int numJointVelocities, const double* jointVelocities) +B3_SHARED_API int b3CreatePoseCommandSetJointVelocities(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, int numJointVelocities, const double* jointVelocities) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -1359,7 +1359,7 @@ int b3CreatePoseCommandSetJointVelocities(b3PhysicsClientHandle physClient, b3Sh return 0; } -int b3CreatePoseCommandSetJointVelocity(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, int jointIndex, double jointVelocity) +B3_SHARED_API int b3CreatePoseCommandSetJointVelocity(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, int jointIndex, double jointVelocity) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -1378,7 +1378,7 @@ int b3CreatePoseCommandSetJointVelocity(b3PhysicsClientHandle physClient, b3Shar -b3SharedMemoryCommandHandle b3CreateSensorCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId) +B3_SHARED_API b3SharedMemoryCommandHandle b3CreateSensorCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -1394,7 +1394,7 @@ b3SharedMemoryCommandHandle b3CreateSensorCommandInit(b3PhysicsClientHandle phys } -int b3CreateSensorEnable6DofJointForceTorqueSensor(b3SharedMemoryCommandHandle commandHandle, int jointIndex, int enable) +B3_SHARED_API int b3CreateSensorEnable6DofJointForceTorqueSensor(b3SharedMemoryCommandHandle commandHandle, int jointIndex, int enable) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -1408,7 +1408,7 @@ int b3CreateSensorEnable6DofJointForceTorqueSensor(b3SharedMemoryCommandHandle c return 0; } -int b3CreateSensorEnableIMUForLink(b3SharedMemoryCommandHandle commandHandle, int linkIndex, int enable) +B3_SHARED_API int b3CreateSensorEnableIMUForLink(b3SharedMemoryCommandHandle commandHandle, int linkIndex, int enable) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -1423,14 +1423,14 @@ int b3CreateSensorEnableIMUForLink(b3SharedMemoryCommandHandle commandHandle, in -void b3DisconnectSharedMemory(b3PhysicsClientHandle physClient) +B3_SHARED_API void b3DisconnectSharedMemory(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient* ) physClient; cl->disconnectSharedMemory(); delete cl; } -b3SharedMemoryStatusHandle b3ProcessServerStatus(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryStatusHandle b3ProcessServerStatus(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient* ) physClient; if (cl && cl->isConnected()) @@ -1444,7 +1444,7 @@ b3SharedMemoryStatusHandle b3ProcessServerStatus(b3PhysicsClientHandle physClien -int b3GetStatusType(b3SharedMemoryStatusHandle statusHandle) +B3_SHARED_API int b3GetStatusType(b3SharedMemoryStatusHandle statusHandle) { const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle; //b3Assert(status); @@ -1455,7 +1455,7 @@ int b3GetStatusType(b3SharedMemoryStatusHandle statusHandle) return CMD_INVALID_STATUS; } -int b3GetStatusBodyIndices(b3SharedMemoryStatusHandle statusHandle, int* bodyIndicesOut, int bodyIndicesCapacity) +B3_SHARED_API int b3GetStatusBodyIndices(b3SharedMemoryStatusHandle statusHandle, int* bodyIndicesOut, int bodyIndicesCapacity) { int numBodies = 0; const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle; @@ -1484,7 +1484,7 @@ int b3GetStatusBodyIndices(b3SharedMemoryStatusHandle statusHandle, int* bodyInd return numBodies; } -int b3GetStatusBodyIndex(b3SharedMemoryStatusHandle statusHandle) +B3_SHARED_API int b3GetStatusBodyIndex(b3SharedMemoryStatusHandle statusHandle) { const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle; b3Assert(status); @@ -1518,7 +1518,7 @@ int b3GetStatusBodyIndex(b3SharedMemoryStatusHandle statusHandle) return bodyId; } -b3SharedMemoryCommandHandle b3RequestCollisionInfoCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId) +B3_SHARED_API b3SharedMemoryCommandHandle b3RequestCollisionInfoCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -1531,7 +1531,7 @@ b3SharedMemoryCommandHandle b3RequestCollisionInfoCommandInit(b3PhysicsClientHan return (b3SharedMemoryCommandHandle) command; } -int b3GetStatusAABB(b3SharedMemoryStatusHandle statusHandle, int linkIndex, double aabbMin[3], double aabbMax[3]) +B3_SHARED_API int b3GetStatusAABB(b3SharedMemoryStatusHandle statusHandle, int linkIndex, double aabbMin[3], double aabbMax[3]) { const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle; const b3SendCollisionInfoArgs &args = status->m_sendCollisionInfoArgs; @@ -1566,7 +1566,7 @@ int b3GetStatusAABB(b3SharedMemoryStatusHandle statusHandle, int linkIndex, doub return 0; } -int b3GetStatusActualState(b3SharedMemoryStatusHandle statusHandle, +B3_SHARED_API int b3GetStatusActualState(b3SharedMemoryStatusHandle statusHandle, int* bodyUniqueId, int* numDegreeOfFreedomQ, int* numDegreeOfFreedomU, @@ -1604,7 +1604,7 @@ int b3GetStatusActualState(b3SharedMemoryStatusHandle statusHandle, return true; } -int b3CanSubmitCommand(b3PhysicsClientHandle physClient) +B3_SHARED_API int b3CanSubmitCommand(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient* ) physClient; if (cl) @@ -1614,7 +1614,7 @@ int b3CanSubmitCommand(b3PhysicsClientHandle physClient) return false; } -int b3SubmitClientCommand(b3PhysicsClientHandle physClient, const b3SharedMemoryCommandHandle commandHandle) +B3_SHARED_API int b3SubmitClientCommand(b3PhysicsClientHandle physClient, const b3SharedMemoryCommandHandle commandHandle) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; PhysicsClient* cl = (PhysicsClient* ) physClient; @@ -1631,7 +1631,7 @@ int b3SubmitClientCommand(b3PhysicsClientHandle physClient, const b3SharedMemory #include "../Utils/b3Clock.h" -b3SharedMemoryStatusHandle b3SubmitClientCommandAndWaitStatus(b3PhysicsClientHandle physClient, const b3SharedMemoryCommandHandle commandHandle) +B3_SHARED_API b3SharedMemoryStatusHandle b3SubmitClientCommandAndWaitStatus(b3PhysicsClientHandle physClient, const b3SharedMemoryCommandHandle commandHandle) { B3_PROFILE("b3SubmitClientCommandAndWaitStatus"); b3Clock clock; @@ -1667,19 +1667,19 @@ b3SharedMemoryStatusHandle b3SubmitClientCommandAndWaitStatus(b3PhysicsClientHan ///return the total number of bodies in the simulation -int b3GetNumBodies(b3PhysicsClientHandle physClient) +B3_SHARED_API int b3GetNumBodies(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient* ) physClient; return cl->getNumBodies(); } -int b3GetNumUserConstraints(b3PhysicsClientHandle physClient) +B3_SHARED_API int b3GetNumUserConstraints(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient* ) physClient; return cl->getNumUserConstraints(); } -int b3GetUserConstraintInfo(b3PhysicsClientHandle physClient, int constraintUniqueId, struct b3UserConstraint* infoPtr) +B3_SHARED_API int b3GetUserConstraintInfo(b3PhysicsClientHandle physClient, int constraintUniqueId, struct b3UserConstraint* infoPtr) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3UserConstraint constraintInfo1; @@ -1699,21 +1699,21 @@ int b3GetUserConstraintInfo(b3PhysicsClientHandle physClient, int constraintUniq } /// return the user constraint id, given the index in range [0 , b3GetNumUserConstraints() ) -int b3GetUserConstraintId(b3PhysicsClientHandle physClient, int serialIndex) +B3_SHARED_API int b3GetUserConstraintId(b3PhysicsClientHandle physClient, int serialIndex) { PhysicsClient* cl = (PhysicsClient* ) physClient; return cl->getUserConstraintId(serialIndex); } /// return the body unique id, given the index in range [0 , b3GetNumBodies() ) -int b3GetBodyUniqueId(b3PhysicsClientHandle physClient, int serialIndex) +B3_SHARED_API int b3GetBodyUniqueId(b3PhysicsClientHandle physClient, int serialIndex) { PhysicsClient* cl = (PhysicsClient* ) physClient; return cl->getBodyUniqueId(serialIndex); } ///given a body unique id, return the body information. See b3BodyInfo in SharedMemoryPublic.h -int b3GetBodyInfo(b3PhysicsClientHandle physClient, int bodyUniqueId, struct b3BodyInfo* info) +B3_SHARED_API int b3GetBodyInfo(b3PhysicsClientHandle physClient, int bodyUniqueId, struct b3BodyInfo* info) { PhysicsClient* cl = (PhysicsClient* ) physClient; return cl->getBodyInfo(bodyUniqueId,*info); @@ -1721,19 +1721,19 @@ int b3GetBodyInfo(b3PhysicsClientHandle physClient, int bodyUniqueId, struct b3B -int b3GetNumJoints(b3PhysicsClientHandle physClient, int bodyId) +B3_SHARED_API int b3GetNumJoints(b3PhysicsClientHandle physClient, int bodyId) { PhysicsClient* cl = (PhysicsClient* ) physClient; return cl->getNumJoints(bodyId); } -int b3GetJointInfo(b3PhysicsClientHandle physClient, int bodyIndex, int jointIndex, struct b3JointInfo* info) +B3_SHARED_API int b3GetJointInfo(b3PhysicsClientHandle physClient, int bodyIndex, int jointIndex, struct b3JointInfo* info) { PhysicsClient* cl = (PhysicsClient* ) physClient; return cl->getJointInfo(bodyIndex, jointIndex, *info); } -b3SharedMemoryCommandHandle b3GetDynamicsInfoCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, int linkIndex) +B3_SHARED_API b3SharedMemoryCommandHandle b3GetDynamicsInfoCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, int linkIndex) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -1746,7 +1746,7 @@ b3SharedMemoryCommandHandle b3GetDynamicsInfoCommandInit(b3PhysicsClientHandle p return (b3SharedMemoryCommandHandle) command; } -int b3GetDynamicsInfo(b3SharedMemoryStatusHandle statusHandle, struct b3DynamicsInfo* info) +B3_SHARED_API int b3GetDynamicsInfo(b3SharedMemoryStatusHandle statusHandle, struct b3DynamicsInfo* info) { const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle; const b3DynamicsInfo &dynamicsInfo = status->m_dynamicsInfo; @@ -1759,7 +1759,7 @@ int b3GetDynamicsInfo(b3SharedMemoryStatusHandle statusHandle, struct b3Dynamics return true; } -b3SharedMemoryCommandHandle b3InitChangeDynamicsInfo(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitChangeDynamicsInfo(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -1774,7 +1774,7 @@ b3SharedMemoryCommandHandle b3InitChangeDynamicsInfo(b3PhysicsClientHandle physC return (b3SharedMemoryCommandHandle) command; } -int b3ChangeDynamicsInfoSetMass(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double mass) +B3_SHARED_API int b3ChangeDynamicsInfoSetMass(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double mass) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_CHANGE_DYNAMICS_INFO); @@ -1786,7 +1786,7 @@ int b3ChangeDynamicsInfoSetMass(b3SharedMemoryCommandHandle commandHandle, int b return 0; } -int b3ChangeDynamicsInfoSetLateralFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double lateralFriction) +B3_SHARED_API int b3ChangeDynamicsInfoSetLateralFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double lateralFriction) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_CHANGE_DYNAMICS_INFO); @@ -1797,7 +1797,7 @@ int b3ChangeDynamicsInfoSetLateralFriction(b3SharedMemoryCommandHandle commandHa return 0; } -int b3ChangeDynamicsInfoSetSpinningFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double friction) +B3_SHARED_API int b3ChangeDynamicsInfoSetSpinningFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double friction) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_CHANGE_DYNAMICS_INFO); @@ -1808,7 +1808,7 @@ int b3ChangeDynamicsInfoSetSpinningFriction(b3SharedMemoryCommandHandle commandH return 0; } -int b3ChangeDynamicsInfoSetRollingFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double friction) +B3_SHARED_API int b3ChangeDynamicsInfoSetRollingFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double friction) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_CHANGE_DYNAMICS_INFO); @@ -1821,7 +1821,7 @@ int b3ChangeDynamicsInfoSetRollingFriction(b3SharedMemoryCommandHandle commandHa } -int b3ChangeDynamicsInfoSetRestitution(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double restitution) +B3_SHARED_API int b3ChangeDynamicsInfoSetRestitution(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double restitution) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_CHANGE_DYNAMICS_INFO); @@ -1831,7 +1831,7 @@ int b3ChangeDynamicsInfoSetRestitution(b3SharedMemoryCommandHandle commandHandle command->m_updateFlags |= CHANGE_DYNAMICS_INFO_SET_RESTITUTION; return 0; } -int b3ChangeDynamicsInfoSetLinearDamping(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId,double linearDamping) +B3_SHARED_API int b3ChangeDynamicsInfoSetLinearDamping(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId,double linearDamping) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_CHANGE_DYNAMICS_INFO); @@ -1843,7 +1843,7 @@ int b3ChangeDynamicsInfoSetLinearDamping(b3SharedMemoryCommandHandle commandHand } -int b3ChangeDynamicsInfoSetAngularDamping(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId,double angularDamping) +B3_SHARED_API int b3ChangeDynamicsInfoSetAngularDamping(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId,double angularDamping) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_CHANGE_DYNAMICS_INFO); @@ -1853,7 +1853,7 @@ int b3ChangeDynamicsInfoSetAngularDamping(b3SharedMemoryCommandHandle commandHan return 0; } -int b3ChangeDynamicsInfoSetContactStiffnessAndDamping(b3SharedMemoryCommandHandle commandHandle,int bodyUniqueId,int linkIndex,double contactStiffness, double contactDamping) +B3_SHARED_API int b3ChangeDynamicsInfoSetContactStiffnessAndDamping(b3SharedMemoryCommandHandle commandHandle,int bodyUniqueId,int linkIndex,double contactStiffness, double contactDamping) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_CHANGE_DYNAMICS_INFO); @@ -1865,7 +1865,7 @@ int b3ChangeDynamicsInfoSetContactStiffnessAndDamping(b3SharedMemoryCommandHandl return 0; } -int b3ChangeDynamicsInfoSetFrictionAnchor(b3SharedMemoryCommandHandle commandHandle,int bodyUniqueId,int linkIndex, int frictionAnchor) +B3_SHARED_API int b3ChangeDynamicsInfoSetFrictionAnchor(b3SharedMemoryCommandHandle commandHandle,int bodyUniqueId,int linkIndex, int frictionAnchor) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command->m_type == CMD_CHANGE_DYNAMICS_INFO); @@ -1878,7 +1878,7 @@ int b3ChangeDynamicsInfoSetFrictionAnchor(b3SharedMemoryCommandHandle commandHan -b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand(b3PhysicsClientHandle physClient, int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, struct b3JointInfo* info) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand(b3PhysicsClientHandle physClient, int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, struct b3JointInfo* info) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -1904,7 +1904,7 @@ b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand(b3PhysicsClientHan return (b3SharedMemoryCommandHandle)command; } -b3SharedMemoryCommandHandle b3InitChangeUserConstraintCommand(b3PhysicsClientHandle physClient, int userConstraintUniqueId) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitChangeUserConstraintCommand(b3PhysicsClientHandle physClient, int userConstraintUniqueId) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -1917,7 +1917,7 @@ b3SharedMemoryCommandHandle b3InitChangeUserConstraintCommand(b3PhysicsClientHa return (b3SharedMemoryCommandHandle)command; } -int b3InitChangeUserConstraintSetPivotInB(b3SharedMemoryCommandHandle commandHandle, double pivotInB[3]) +B3_SHARED_API int b3InitChangeUserConstraintSetPivotInB(b3SharedMemoryCommandHandle commandHandle, double pivotInB[3]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -1932,7 +1932,7 @@ int b3InitChangeUserConstraintSetPivotInB(b3SharedMemoryCommandHandle commandHan command->m_userConstraintArguments.m_childFrame[2] = pivotInB[2]; return 0; } -int b3InitChangeUserConstraintSetFrameInB(b3SharedMemoryCommandHandle commandHandle, double frameOrnInB[4]) +B3_SHARED_API int b3InitChangeUserConstraintSetFrameInB(b3SharedMemoryCommandHandle commandHandle, double frameOrnInB[4]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -1949,7 +1949,7 @@ int b3InitChangeUserConstraintSetFrameInB(b3SharedMemoryCommandHandle commandHan return 0; } -int b3InitChangeUserConstraintSetMaxForce(b3SharedMemoryCommandHandle commandHandle, double maxAppliedForce) +B3_SHARED_API int b3InitChangeUserConstraintSetMaxForce(b3SharedMemoryCommandHandle commandHandle, double maxAppliedForce) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -1961,7 +1961,7 @@ int b3InitChangeUserConstraintSetMaxForce(b3SharedMemoryCommandHandle commandHan return 0; } -int b3InitChangeUserConstraintSetGearRatio(b3SharedMemoryCommandHandle commandHandle, double gearRatio) +B3_SHARED_API int b3InitChangeUserConstraintSetGearRatio(b3SharedMemoryCommandHandle commandHandle, double gearRatio) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -1974,7 +1974,7 @@ int b3InitChangeUserConstraintSetGearRatio(b3SharedMemoryCommandHandle commandHa return 0; } -int b3InitChangeUserConstraintSetGearAuxLink(b3SharedMemoryCommandHandle commandHandle, int gearAuxLink) +B3_SHARED_API int b3InitChangeUserConstraintSetGearAuxLink(b3SharedMemoryCommandHandle commandHandle, int gearAuxLink) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -1988,7 +1988,7 @@ int b3InitChangeUserConstraintSetGearAuxLink(b3SharedMemoryCommandHandle command } -b3SharedMemoryCommandHandle b3InitRemoveUserConstraintCommand(b3PhysicsClientHandle physClient, int userConstraintUniqueId) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitRemoveUserConstraintCommand(b3PhysicsClientHandle physClient, int userConstraintUniqueId) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -2002,7 +2002,7 @@ b3SharedMemoryCommandHandle b3InitRemoveUserConstraintCommand(b3PhysicsClientHa return (b3SharedMemoryCommandHandle)command; } -b3SharedMemoryCommandHandle b3InitRemoveBodyCommand(b3PhysicsClientHandle physClient, int bodyUniqueId) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitRemoveBodyCommand(b3PhysicsClientHandle physClient, int bodyUniqueId) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -2019,7 +2019,7 @@ b3SharedMemoryCommandHandle b3InitRemoveBodyCommand(b3PhysicsClientHandle physCl return (b3SharedMemoryCommandHandle)command; } -int b3GetStatusUserConstraintUniqueId(b3SharedMemoryStatusHandle statusHandle) +B3_SHARED_API int b3GetStatusUserConstraintUniqueId(b3SharedMemoryStatusHandle statusHandle) { const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle; b3Assert(status); @@ -2034,7 +2034,7 @@ int b3GetStatusUserConstraintUniqueId(b3SharedMemoryStatusHandle statusHandle) } -b3SharedMemoryCommandHandle b3PickBody(b3PhysicsClientHandle physClient, double rayFromWorldX, +B3_SHARED_API b3SharedMemoryCommandHandle b3PickBody(b3PhysicsClientHandle physClient, double rayFromWorldX, double rayFromWorldY, double rayFromWorldZ, double rayToWorldX, double rayToWorldY, double rayToWorldZ) { @@ -2053,7 +2053,7 @@ b3SharedMemoryCommandHandle b3PickBody(b3PhysicsClientHandle physClient, double return (b3SharedMemoryCommandHandle)command; } -b3SharedMemoryCommandHandle b3MovePickedBody(b3PhysicsClientHandle physClient, double rayFromWorldX, +B3_SHARED_API b3SharedMemoryCommandHandle b3MovePickedBody(b3PhysicsClientHandle physClient, double rayFromWorldX, double rayFromWorldY, double rayFromWorldZ, double rayToWorldX, double rayToWorldY, double rayToWorldZ) @@ -2073,7 +2073,7 @@ b3SharedMemoryCommandHandle b3MovePickedBody(b3PhysicsClientHandle physClient, d return (b3SharedMemoryCommandHandle)command; } -b3SharedMemoryCommandHandle b3RemovePickingConstraint(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryCommandHandle b3RemovePickingConstraint(b3PhysicsClientHandle physClient) { PhysicsClient *cl = (PhysicsClient *)physClient; b3Assert(cl); @@ -2084,7 +2084,7 @@ b3SharedMemoryCommandHandle b3RemovePickingConstraint(b3PhysicsClientHandle phys return (b3SharedMemoryCommandHandle)command; } -b3SharedMemoryCommandHandle b3CreateRaycastCommandInit(b3PhysicsClientHandle physClient, double rayFromWorldX, +B3_SHARED_API b3SharedMemoryCommandHandle b3CreateRaycastCommandInit(b3PhysicsClientHandle physClient, double rayFromWorldX, double rayFromWorldY, double rayFromWorldZ, double rayToWorldX, double rayToWorldY, double rayToWorldZ) { @@ -2105,7 +2105,7 @@ b3SharedMemoryCommandHandle b3CreateRaycastCommandInit(b3PhysicsClientHandle phy return (b3SharedMemoryCommandHandle)command; } -b3SharedMemoryCommandHandle b3CreateRaycastBatchCommandInit(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryCommandHandle b3CreateRaycastBatchCommandInit(b3PhysicsClientHandle physClient) { PhysicsClient *cl = (PhysicsClient *)physClient; b3Assert(cl); @@ -2118,7 +2118,7 @@ b3SharedMemoryCommandHandle b3CreateRaycastBatchCommandInit(b3PhysicsClientHandl return (b3SharedMemoryCommandHandle)command; } -void b3RaycastBatchAddRay(b3SharedMemoryCommandHandle commandHandle, const double rayFromWorld[3], const double rayToWorld[3]) +B3_SHARED_API void b3RaycastBatchAddRay(b3SharedMemoryCommandHandle commandHandle, const double rayFromWorld[3], const double rayToWorld[3]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -2140,7 +2140,7 @@ void b3RaycastBatchAddRay(b3SharedMemoryCommandHandle commandHandle, const doubl } -void b3GetRaycastInformation(b3PhysicsClientHandle physClient, struct b3RaycastInformation* raycastInfo) +B3_SHARED_API void b3GetRaycastInformation(b3PhysicsClientHandle physClient, struct b3RaycastInformation* raycastInfo) { PhysicsClient* cl = (PhysicsClient* ) physClient; if (cl) @@ -2151,7 +2151,7 @@ void b3GetRaycastInformation(b3PhysicsClientHandle physClient, struct b3RaycastI ///If you re-connected to an existing server, or server changed otherwise, sync the body info -b3SharedMemoryCommandHandle b3InitSyncBodyInfoCommand(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitSyncBodyInfoCommand(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -2163,7 +2163,7 @@ b3SharedMemoryCommandHandle b3InitSyncBodyInfoCommand(b3PhysicsClientHandle phys return (b3SharedMemoryCommandHandle) command; } -b3SharedMemoryCommandHandle b3InitRequestDebugLinesCommand(b3PhysicsClientHandle physClient, int debugMode) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestDebugLinesCommand(b3PhysicsClientHandle physClient, int debugMode) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -2176,7 +2176,7 @@ b3SharedMemoryCommandHandle b3InitRequestDebugLinesCommand(b3PhysicsClientHandle command->m_requestDebugLinesArguments.m_startingLineIndex = 0; return (b3SharedMemoryCommandHandle) command; } -void b3GetDebugLines(b3PhysicsClientHandle physClient, struct b3DebugLines* lines) +B3_SHARED_API void b3GetDebugLines(b3PhysicsClientHandle physClient, struct b3DebugLines* lines) { PhysicsClient* cl = (PhysicsClient* ) physClient; @@ -2194,7 +2194,7 @@ void b3GetDebugLines(b3PhysicsClientHandle physClient, struct b3DebugLines* l /// Add/remove user-specific debug lines and debug text messages -b3SharedMemoryCommandHandle b3InitUserDebugDrawAddLine3D(b3PhysicsClientHandle physClient, double fromXYZ[3], double toXYZ[3], double colorRGB[3], double lineWidth, double lifeTime) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawAddLine3D(b3PhysicsClientHandle physClient, double fromXYZ[3], double toXYZ[3], double colorRGB[3], double lineWidth, double lifeTime) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -2225,7 +2225,7 @@ b3SharedMemoryCommandHandle b3InitUserDebugDrawAddLine3D(b3PhysicsClientHandle p return (b3SharedMemoryCommandHandle) command; } -b3SharedMemoryCommandHandle b3InitUserDebugDrawAddText3D(b3PhysicsClientHandle physClient, const char* txt, double positionXYZ[3], double colorRGB[3], double textSize, double lifeTime) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawAddText3D(b3PhysicsClientHandle physClient, const char* txt, double positionXYZ[3], double colorRGB[3], double textSize, double lifeTime) { PhysicsClient* cl = (PhysicsClient* ) physClient; @@ -2263,7 +2263,7 @@ b3SharedMemoryCommandHandle b3InitUserDebugDrawAddText3D(b3PhysicsClientHandle p return (b3SharedMemoryCommandHandle) command; } -void b3UserDebugTextSetOptionFlags(b3SharedMemoryCommandHandle commandHandle, int optionFlags) +B3_SHARED_API void b3UserDebugTextSetOptionFlags(b3SharedMemoryCommandHandle commandHandle, int optionFlags) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -2273,7 +2273,7 @@ void b3UserDebugTextSetOptionFlags(b3SharedMemoryCommandHandle commandHandle, in command->m_updateFlags |= USER_DEBUG_HAS_OPTION_FLAGS; } -void b3UserDebugTextSetOrientation(b3SharedMemoryCommandHandle commandHandle, double orientation[4]) +B3_SHARED_API void b3UserDebugTextSetOrientation(b3SharedMemoryCommandHandle commandHandle, double orientation[4]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -2288,7 +2288,7 @@ void b3UserDebugTextSetOrientation(b3SharedMemoryCommandHandle commandHandle, do } -void b3UserDebugItemSetParentObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex) +B3_SHARED_API void b3UserDebugItemSetParentObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -2300,7 +2300,7 @@ void b3UserDebugItemSetParentObject(b3SharedMemoryCommandHandle commandHandle, i } -b3SharedMemoryCommandHandle b3InitUserDebugAddParameter(b3PhysicsClientHandle physClient, const char* txt, double rangeMin, double rangeMax, double startValue) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugAddParameter(b3PhysicsClientHandle physClient, const char* txt, double rangeMin, double rangeMax, double startValue) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -2325,7 +2325,7 @@ b3SharedMemoryCommandHandle b3InitUserDebugAddParameter(b3PhysicsClientHandle ph return (b3SharedMemoryCommandHandle)command; } -b3SharedMemoryCommandHandle b3InitUserDebugReadParameter(b3PhysicsClientHandle physClient, int debugItemUniqueId) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugReadParameter(b3PhysicsClientHandle physClient, int debugItemUniqueId) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -2338,7 +2338,7 @@ b3SharedMemoryCommandHandle b3InitUserDebugReadParameter(b3PhysicsClientHandle p return (b3SharedMemoryCommandHandle) command; } -int b3GetStatusDebugParameterValue(b3SharedMemoryStatusHandle statusHandle, double* paramValue) +B3_SHARED_API int b3GetStatusDebugParameterValue(b3SharedMemoryStatusHandle statusHandle, double* paramValue) { const SharedMemoryStatus* status = (const SharedMemoryStatus*)statusHandle; btAssert(status->m_type == CMD_USER_DEBUG_DRAW_PARAMETER_COMPLETED); @@ -2351,7 +2351,7 @@ int b3GetStatusDebugParameterValue(b3SharedMemoryStatusHandle statusHandle, doub } -b3SharedMemoryCommandHandle b3InitUserDebugDrawRemove(b3PhysicsClientHandle physClient, int debugItemUniqueId) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawRemove(b3PhysicsClientHandle physClient, int debugItemUniqueId) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -2365,7 +2365,7 @@ b3SharedMemoryCommandHandle b3InitUserDebugDrawRemove(b3PhysicsClientHandle phys } -b3SharedMemoryCommandHandle b3InitUserDebugDrawRemoveAll(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawRemoveAll(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -2377,7 +2377,7 @@ b3SharedMemoryCommandHandle b3InitUserDebugDrawRemoveAll(b3PhysicsClientHandle p return (b3SharedMemoryCommandHandle) command; } -int b3GetDebugItemUniqueId(b3SharedMemoryStatusHandle statusHandle) +B3_SHARED_API int b3GetDebugItemUniqueId(b3SharedMemoryStatusHandle statusHandle) { const SharedMemoryStatus* status = (const SharedMemoryStatus*)statusHandle; btAssert(status->m_type == CMD_USER_DEBUG_DRAW_COMPLETED); @@ -2387,7 +2387,7 @@ int b3GetDebugItemUniqueId(b3SharedMemoryStatusHandle statusHandle) return status->m_userDebugDrawArgs.m_debugItemUniqueId; } -b3SharedMemoryCommandHandle b3InitDebugDrawingCommand(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitDebugDrawingCommand(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient*)physClient; b3Assert(cl); @@ -2401,7 +2401,7 @@ b3SharedMemoryCommandHandle b3InitDebugDrawingCommand(b3PhysicsClientHandle phys -void b3SetDebugObjectColor(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex, double objectColorRGB[3]) +B3_SHARED_API void b3SetDebugObjectColor(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex, double objectColorRGB[3]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -2414,7 +2414,7 @@ void b3SetDebugObjectColor(b3SharedMemoryCommandHandle commandHandle, int object command->m_userDebugDrawArgs.m_objectDebugColorRGB[2] = objectColorRGB[2]; } -void b3RemoveDebugObjectColor(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex) +B3_SHARED_API void b3RemoveDebugObjectColor(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -2429,7 +2429,7 @@ void b3RemoveDebugObjectColor(b3SharedMemoryCommandHandle commandHandle, int obj ///request an image from a simulated camera, using a software renderer. -b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -2442,7 +2442,7 @@ b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physC return (b3SharedMemoryCommandHandle) command; } -void b3RequestCameraImageSelectRenderer(b3SharedMemoryCommandHandle commandHandle, int renderer) +B3_SHARED_API void b3RequestCameraImageSelectRenderer(b3SharedMemoryCommandHandle commandHandle, int renderer) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -2454,7 +2454,7 @@ void b3RequestCameraImageSelectRenderer(b3SharedMemoryCommandHandle commandHandl } } -void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle commandHandle, float viewMatrix[16], float projectionMatrix[16]) +B3_SHARED_API void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle commandHandle, float viewMatrix[16], float projectionMatrix[16]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -2467,7 +2467,7 @@ void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle commandHa command->m_updateFlags |= REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES; } -void b3RequestCameraImageSetLightDirection(b3SharedMemoryCommandHandle commandHandle, const float lightDirection[3]) +B3_SHARED_API void b3RequestCameraImageSetLightDirection(b3SharedMemoryCommandHandle commandHandle, const float lightDirection[3]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -2479,7 +2479,7 @@ void b3RequestCameraImageSetLightDirection(b3SharedMemoryCommandHandle commandHa command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_LIGHT_DIRECTION; } -void b3RequestCameraImageSetLightColor(b3SharedMemoryCommandHandle commandHandle, const float lightColor[3]) +B3_SHARED_API void b3RequestCameraImageSetLightColor(b3SharedMemoryCommandHandle commandHandle, const float lightColor[3]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -2491,7 +2491,7 @@ void b3RequestCameraImageSetLightColor(b3SharedMemoryCommandHandle commandHandle command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_LIGHT_COLOR; } -void b3RequestCameraImageSetLightDistance(b3SharedMemoryCommandHandle commandHandle, float lightDistance) +B3_SHARED_API void b3RequestCameraImageSetLightDistance(b3SharedMemoryCommandHandle commandHandle, float lightDistance) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -2500,7 +2500,7 @@ void b3RequestCameraImageSetLightDistance(b3SharedMemoryCommandHandle commandHan command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_LIGHT_DISTANCE; } -void b3RequestCameraImageSetLightAmbientCoeff(b3SharedMemoryCommandHandle commandHandle, float lightAmbientCoeff) +B3_SHARED_API void b3RequestCameraImageSetLightAmbientCoeff(b3SharedMemoryCommandHandle commandHandle, float lightAmbientCoeff) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -2509,7 +2509,7 @@ void b3RequestCameraImageSetLightAmbientCoeff(b3SharedMemoryCommandHandle comman command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_AMBIENT_COEFF; } -void b3RequestCameraImageSetLightDiffuseCoeff(b3SharedMemoryCommandHandle commandHandle, float lightDiffuseCoeff) +B3_SHARED_API void b3RequestCameraImageSetLightDiffuseCoeff(b3SharedMemoryCommandHandle commandHandle, float lightDiffuseCoeff) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -2518,7 +2518,7 @@ void b3RequestCameraImageSetLightDiffuseCoeff(b3SharedMemoryCommandHandle comman command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_DIFFUSE_COEFF; } -void b3RequestCameraImageSetLightSpecularCoeff(b3SharedMemoryCommandHandle commandHandle, float lightSpecularCoeff) +B3_SHARED_API void b3RequestCameraImageSetLightSpecularCoeff(b3SharedMemoryCommandHandle commandHandle, float lightSpecularCoeff) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -2527,7 +2527,7 @@ void b3RequestCameraImageSetLightSpecularCoeff(b3SharedMemoryCommandHandle comma command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_SPECULAR_COEFF; } -void b3RequestCameraImageSetShadow(b3SharedMemoryCommandHandle commandHandle, int hasShadow) +B3_SHARED_API void b3RequestCameraImageSetShadow(b3SharedMemoryCommandHandle commandHandle, int hasShadow) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -2536,7 +2536,7 @@ void b3RequestCameraImageSetShadow(b3SharedMemoryCommandHandle commandHandle, in command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_SHADOW; } -void b3ComputePositionFromViewMatrix(const float viewMatrix[16], float cameraPosition[3], float cameraTargetPosition[3], float cameraUp[3]) +B3_SHARED_API void b3ComputePositionFromViewMatrix(const float viewMatrix[16], float cameraPosition[3], float cameraTargetPosition[3], float cameraUp[3]) { b3Matrix3x3 r(viewMatrix[0], viewMatrix[4], viewMatrix[8], viewMatrix[1], viewMatrix[5], viewMatrix[9], viewMatrix[2], viewMatrix[6], viewMatrix[10]); b3Vector3 p = b3MakeVector3(viewMatrix[12], viewMatrix[13], viewMatrix[14]); @@ -2560,7 +2560,7 @@ void b3ComputePositionFromViewMatrix(const float viewMatrix[16], float cameraPos cameraUp[2] = u[2]; } -void b3ComputeViewMatrixFromPositions(const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3], float viewMatrix[16]) +B3_SHARED_API void b3ComputeViewMatrixFromPositions(const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3], float viewMatrix[16]) { b3Vector3 eye = b3MakeVector3(cameraPosition[0], cameraPosition[1], cameraPosition[2]); b3Vector3 center = b3MakeVector3(cameraTargetPosition[0], cameraTargetPosition[1], cameraTargetPosition[2]); @@ -2593,7 +2593,7 @@ void b3ComputeViewMatrixFromPositions(const float cameraPosition[3], const float } -void b3ComputeViewMatrixFromYawPitchRoll(const float cameraTargetPosition[3], float distance, float yaw, float pitch, float roll, int upAxis, float viewMatrix[16]) +B3_SHARED_API void b3ComputeViewMatrixFromYawPitchRoll(const float cameraTargetPosition[3], float distance, float yaw, float pitch, float roll, int upAxis, float viewMatrix[16]) { b3Vector3 camUpVector; b3Vector3 camForward; @@ -2649,7 +2649,7 @@ void b3ComputeViewMatrixFromYawPitchRoll(const float cameraTargetPosition[3], fl } -void b3ComputeProjectionMatrix(float left, float right, float bottom, float top, float nearVal, float farVal, float projectionMatrix[16]) +B3_SHARED_API void b3ComputeProjectionMatrix(float left, float right, float bottom, float top, float nearVal, float farVal, float projectionMatrix[16]) { projectionMatrix[0 * 4 + 0] = (float(2) * nearVal) / (right - left); projectionMatrix[0 * 4 + 1] = float(0); @@ -2673,7 +2673,7 @@ void b3ComputeProjectionMatrix(float left, float right, float bottom, float top, } -void b3ComputeProjectionMatrixFOV(float fov, float aspect, float nearVal, float farVal, float projectionMatrix[16]) +B3_SHARED_API void b3ComputeProjectionMatrixFOV(float fov, float aspect, float nearVal, float farVal, float projectionMatrix[16]) { float yScale = 1.0 / tan((3.141592538 / 180.0) * fov / 2); float xScale = yScale / aspect; @@ -2700,7 +2700,7 @@ void b3ComputeProjectionMatrixFOV(float fov, float aspect, float nearVal, float } -void b3RequestCameraImageSetViewMatrix2(b3SharedMemoryCommandHandle commandHandle, const float cameraTargetPosition[3], float distance, float yaw, float pitch, float roll, int upAxis) +B3_SHARED_API void b3RequestCameraImageSetViewMatrix2(b3SharedMemoryCommandHandle commandHandle, const float cameraTargetPosition[3], float distance, float yaw, float pitch, float roll, int upAxis) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -2714,7 +2714,7 @@ void b3RequestCameraImageSetViewMatrix2(b3SharedMemoryCommandHandle commandHandl -void b3RequestCameraImageSetViewMatrix(b3SharedMemoryCommandHandle commandHandle, const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3]) +B3_SHARED_API void b3RequestCameraImageSetViewMatrix(b3SharedMemoryCommandHandle commandHandle, const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3]) { float viewMatrix[16]; b3ComputeViewMatrixFromPositions(cameraPosition, cameraTargetPosition, cameraUp, viewMatrix); @@ -2729,7 +2729,7 @@ void b3RequestCameraImageSetViewMatrix(b3SharedMemoryCommandHandle commandHandle } -void b3RequestCameraImageSetProjectionMatrix(b3SharedMemoryCommandHandle commandHandle, float left, float right, float bottom, float top, float nearVal, float farVal) +B3_SHARED_API void b3RequestCameraImageSetProjectionMatrix(b3SharedMemoryCommandHandle commandHandle, float left, float right, float bottom, float top, float nearVal, float farVal) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; @@ -2741,7 +2741,7 @@ void b3RequestCameraImageSetProjectionMatrix(b3SharedMemoryCommandHandle command command->m_updateFlags |= REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES; } -void b3RequestCameraImageSetFOVProjectionMatrix(b3SharedMemoryCommandHandle commandHandle, float fov, float aspect, float nearVal, float farVal) +B3_SHARED_API void b3RequestCameraImageSetFOVProjectionMatrix(b3SharedMemoryCommandHandle commandHandle, float fov, float aspect, float nearVal, float farVal) { @@ -2754,7 +2754,7 @@ void b3RequestCameraImageSetFOVProjectionMatrix(b3SharedMemoryCommandHandle comm command->m_updateFlags |= REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES; } -void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle commandHandle, int width, int height ) +B3_SHARED_API void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle commandHandle, int width, int height ) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -2764,7 +2764,7 @@ void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle commandH command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT; } -void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData) +B3_SHARED_API void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData) { PhysicsClient* cl = (PhysicsClient* ) physClient; if (cl) @@ -2774,7 +2774,7 @@ void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImage } ///request an contact point information -b3SharedMemoryCommandHandle b3InitRequestContactPointInformation(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestContactPointInformation(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -2791,7 +2791,7 @@ b3SharedMemoryCommandHandle b3InitRequestContactPointInformation(b3PhysicsClient return (b3SharedMemoryCommandHandle) command; } -void b3SetContactFilterBodyA(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdA) +B3_SHARED_API void b3SetContactFilterBodyA(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdA) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -2799,7 +2799,7 @@ void b3SetContactFilterBodyA(b3SharedMemoryCommandHandle commandHandle, int body command->m_requestContactPointArguments.m_objectAIndexFilter = bodyUniqueIdA; } -void b3SetContactFilterLinkA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA) +B3_SHARED_API void b3SetContactFilterLinkA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -2808,7 +2808,7 @@ void b3SetContactFilterLinkA(b3SharedMemoryCommandHandle commandHandle, int link command->m_requestContactPointArguments.m_linkIndexAIndexFilter= linkIndexA; } -void b3SetContactFilterLinkB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB) +B3_SHARED_API void b3SetContactFilterLinkB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -2817,12 +2817,12 @@ void b3SetContactFilterLinkB(b3SharedMemoryCommandHandle commandHandle, int link command->m_requestContactPointArguments.m_linkIndexBIndexFilter = linkIndexB; } -void b3SetClosestDistanceFilterLinkA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA) +B3_SHARED_API void b3SetClosestDistanceFilterLinkA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA) { b3SetContactFilterLinkA(commandHandle, linkIndexA); } -void b3SetClosestDistanceFilterLinkB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB) +B3_SHARED_API void b3SetClosestDistanceFilterLinkB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB) { b3SetContactFilterLinkB(commandHandle, linkIndexB); } @@ -2830,7 +2830,7 @@ void b3SetClosestDistanceFilterLinkB(b3SharedMemoryCommandHandle commandHandle, -void b3SetContactFilterBodyB(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdB) +B3_SHARED_API void b3SetContactFilterBodyB(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdB) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -2840,7 +2840,7 @@ void b3SetContactFilterBodyB(b3SharedMemoryCommandHandle commandHandle, int body ///compute the closest points between two bodies -b3SharedMemoryCommandHandle b3InitClosestDistanceQuery(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitClosestDistanceQuery(b3PhysicsClientHandle physClient) { b3SharedMemoryCommandHandle commandHandle =b3InitRequestContactPointInformation(physClient); struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; @@ -2851,17 +2851,17 @@ b3SharedMemoryCommandHandle b3InitClosestDistanceQuery(b3PhysicsClientHandle phy return commandHandle; } -void b3SetClosestDistanceFilterBodyA(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdA) +B3_SHARED_API void b3SetClosestDistanceFilterBodyA(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdA) { b3SetContactFilterBodyA(commandHandle,bodyUniqueIdA); } -void b3SetClosestDistanceFilterBodyB(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdB) +B3_SHARED_API void b3SetClosestDistanceFilterBodyB(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdB) { b3SetContactFilterBodyB(commandHandle,bodyUniqueIdB); } -void b3SetClosestDistanceThreshold(b3SharedMemoryCommandHandle commandHandle, double distance) +B3_SHARED_API void b3SetClosestDistanceThreshold(b3SharedMemoryCommandHandle commandHandle, double distance) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -2872,7 +2872,7 @@ void b3SetClosestDistanceThreshold(b3SharedMemoryCommandHandle commandHandle, do ///get all the bodies that touch a given axis aligned bounding box specified in world space (min and max coordinates) -b3SharedMemoryCommandHandle b3InitAABBOverlapQuery(b3PhysicsClientHandle physClient, const double aabbMin[3], const double aabbMax[3]) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitAABBOverlapQuery(b3PhysicsClientHandle physClient, const double aabbMin[3], const double aabbMax[3]) { PhysicsClient* cl = (PhysicsClient*)physClient; b3Assert(cl); @@ -2892,7 +2892,7 @@ b3SharedMemoryCommandHandle b3InitAABBOverlapQuery(b3PhysicsClientHandle physCli return (b3SharedMemoryCommandHandle)command; } -void b3GetAABBOverlapResults(b3PhysicsClientHandle physClient, struct b3AABBOverlapData* data) +B3_SHARED_API void b3GetAABBOverlapResults(b3PhysicsClientHandle physClient, struct b3AABBOverlapData* data) { PhysicsClient* cl = (PhysicsClient*)physClient; if (cl) @@ -2903,7 +2903,7 @@ void b3GetAABBOverlapResults(b3PhysicsClientHandle physClient, struct b3AABBOver -void b3GetContactPointInformation(b3PhysicsClientHandle physClient, struct b3ContactInformation* contactPointData) +B3_SHARED_API void b3GetContactPointInformation(b3PhysicsClientHandle physClient, struct b3ContactInformation* contactPointData) { PhysicsClient* cl = (PhysicsClient* ) physClient; if (cl) @@ -2912,7 +2912,7 @@ void b3GetContactPointInformation(b3PhysicsClientHandle physClient, struct b3Con } } -void b3GetClosestPointInformation(b3PhysicsClientHandle physClient, struct b3ContactInformation* contactPointInfo) +B3_SHARED_API void b3GetClosestPointInformation(b3PhysicsClientHandle physClient, struct b3ContactInformation* contactPointInfo) { b3GetContactPointInformation(physClient,contactPointInfo); } @@ -2920,7 +2920,7 @@ void b3GetClosestPointInformation(b3PhysicsClientHandle physClient, struct b3Con //request visual shape information -b3SharedMemoryCommandHandle b3InitRequestVisualShapeInformation(b3PhysicsClientHandle physClient, int bodyUniqueIdA) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestVisualShapeInformation(b3PhysicsClientHandle physClient, int bodyUniqueIdA) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -2934,7 +2934,7 @@ b3SharedMemoryCommandHandle b3InitRequestVisualShapeInformation(b3PhysicsClientH return (b3SharedMemoryCommandHandle) command; } -void b3GetVisualShapeInformation(b3PhysicsClientHandle physClient, struct b3VisualShapeInformation* visualShapeInfo) +B3_SHARED_API void b3GetVisualShapeInformation(b3PhysicsClientHandle physClient, struct b3VisualShapeInformation* visualShapeInfo) { PhysicsClient* cl = (PhysicsClient*)physClient; if (cl) @@ -2943,7 +2943,7 @@ void b3GetVisualShapeInformation(b3PhysicsClientHandle physClient, struct b3Visu } } -b3SharedMemoryCommandHandle b3CreateChangeTextureCommandInit(b3PhysicsClientHandle physClient, int textureUniqueId, int width, int height, const char* rgbPixels) +B3_SHARED_API b3SharedMemoryCommandHandle b3CreateChangeTextureCommandInit(b3PhysicsClientHandle physClient, int textureUniqueId, int width, int height, const char* rgbPixels) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -2962,7 +2962,7 @@ b3SharedMemoryCommandHandle b3CreateChangeTextureCommandInit(b3PhysicsClientHand } -b3SharedMemoryCommandHandle b3InitLoadTexture(b3PhysicsClientHandle physClient, const char* filename) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitLoadTexture(b3PhysicsClientHandle physClient, const char* filename) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -2982,7 +2982,7 @@ b3SharedMemoryCommandHandle b3InitLoadTexture(b3PhysicsClientHandle physClient, return (b3SharedMemoryCommandHandle) command; } -int b3GetStatusTextureUniqueId(b3SharedMemoryStatusHandle statusHandle) +B3_SHARED_API int b3GetStatusTextureUniqueId(b3SharedMemoryStatusHandle statusHandle) { int uid = -1; const SharedMemoryStatus* status = (const SharedMemoryStatus*)statusHandle; @@ -2994,7 +2994,7 @@ int b3GetStatusTextureUniqueId(b3SharedMemoryStatusHandle statusHandle) return uid; } -b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient, int bodyUniqueId, int jointIndex, int shapeIndex, int textureUniqueId) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient, int bodyUniqueId, int jointIndex, int shapeIndex, int textureUniqueId) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -3015,7 +3015,7 @@ b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physCl return (b3SharedMemoryCommandHandle) command; } -void b3UpdateVisualShapeRGBAColor(b3SharedMemoryCommandHandle commandHandle, double rgbaColor[4]) +B3_SHARED_API void b3UpdateVisualShapeRGBAColor(b3SharedMemoryCommandHandle commandHandle, double rgbaColor[4]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3031,7 +3031,7 @@ void b3UpdateVisualShapeRGBAColor(b3SharedMemoryCommandHandle commandHandle, dou } } -void b3UpdateVisualShapeSpecularColor(b3SharedMemoryCommandHandle commandHandle, double specularColor[3]) +B3_SHARED_API void b3UpdateVisualShapeSpecularColor(b3SharedMemoryCommandHandle commandHandle, double specularColor[3]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3046,7 +3046,7 @@ void b3UpdateVisualShapeSpecularColor(b3SharedMemoryCommandHandle commandHandle, } } -b3SharedMemoryCommandHandle b3ApplyExternalForceCommandInit(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryCommandHandle b3ApplyExternalForceCommandInit(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -3060,7 +3060,7 @@ b3SharedMemoryCommandHandle b3ApplyExternalForceCommandInit(b3PhysicsClientHandl return (b3SharedMemoryCommandHandle) command; } -void b3ApplyExternalForce(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkId, const double force[3], const double position[3], int flag) +B3_SHARED_API void b3ApplyExternalForce(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkId, const double force[3], const double position[3], int flag) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3077,7 +3077,7 @@ void b3ApplyExternalForce(b3SharedMemoryCommandHandle commandHandle, int bodyUni command->m_externalForceArguments.m_numForcesAndTorques++; } -void b3ApplyExternalTorque(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkId, const double torque[3], int flag) +B3_SHARED_API void b3ApplyExternalTorque(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkId, const double torque[3], int flag) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3097,7 +3097,7 @@ void b3ApplyExternalTorque(b3SharedMemoryCommandHandle commandHandle, int bodyUn ///compute the forces to achieve an acceleration, given a state q and qdot using inverse dynamics -b3SharedMemoryCommandHandle b3CalculateInverseDynamicsCommandInit(b3PhysicsClientHandle physClient, int bodyIndex, +B3_SHARED_API b3SharedMemoryCommandHandle b3CalculateInverseDynamicsCommandInit(b3PhysicsClientHandle physClient, int bodyIndex, const double* jointPositionsQ, const double* jointVelocitiesQdot, const double* jointAccelerations) { PhysicsClient* cl = (PhysicsClient*)physClient; @@ -3120,7 +3120,7 @@ b3SharedMemoryCommandHandle b3CalculateInverseDynamicsCommandInit(b3PhysicsClien return (b3SharedMemoryCommandHandle)command; } -int b3GetStatusInverseDynamicsJointForces(b3SharedMemoryStatusHandle statusHandle, +B3_SHARED_API int b3GetStatusInverseDynamicsJointForces(b3SharedMemoryStatusHandle statusHandle, int* bodyUniqueId, int* dofCount, double* jointForces) @@ -3151,7 +3151,7 @@ int b3GetStatusInverseDynamicsJointForces(b3SharedMemoryStatusHandle statusHandl return true; } -b3SharedMemoryCommandHandle b3CalculateJacobianCommandInit(b3PhysicsClientHandle physClient, int bodyIndex, int linkIndex, const double* localPosition, const double* jointPositionsQ, const double* jointVelocitiesQdot, const double* jointAccelerations) +B3_SHARED_API b3SharedMemoryCommandHandle b3CalculateJacobianCommandInit(b3PhysicsClientHandle physClient, int bodyIndex, int linkIndex, const double* localPosition, const double* jointPositionsQ, const double* jointVelocitiesQdot, const double* jointAccelerations) { PhysicsClient* cl = (PhysicsClient*)physClient; b3Assert(cl); @@ -3178,7 +3178,7 @@ b3SharedMemoryCommandHandle b3CalculateJacobianCommandInit(b3PhysicsClientHandle } -int b3GetStatusJacobian(b3SharedMemoryStatusHandle statusHandle, double* linearJacobian, double* angularJacobian) +B3_SHARED_API int b3GetStatusJacobian(b3SharedMemoryStatusHandle statusHandle, double* linearJacobian, double* angularJacobian) { const SharedMemoryStatus* status = (const SharedMemoryStatus*)statusHandle; btAssert(status->m_type == CMD_CALCULATED_JACOBIAN_COMPLETED); @@ -3205,7 +3205,7 @@ int b3GetStatusJacobian(b3SharedMemoryStatusHandle statusHandle, double* linearJ } ///compute the joint positions to move the end effector to a desired target using inverse kinematics -b3SharedMemoryCommandHandle b3CalculateInverseKinematicsCommandInit(b3PhysicsClientHandle physClient, int bodyIndex) +B3_SHARED_API b3SharedMemoryCommandHandle b3CalculateInverseKinematicsCommandInit(b3PhysicsClientHandle physClient, int bodyIndex) { PhysicsClient* cl = (PhysicsClient*)physClient; b3Assert(cl); @@ -3221,7 +3221,7 @@ b3SharedMemoryCommandHandle b3CalculateInverseKinematicsCommandInit(b3PhysicsCli } -void b3CalculateInverseKinematicsAddTargetPurePosition(b3SharedMemoryCommandHandle commandHandle, int endEffectorLinkIndex, const double targetPosition[3]) +B3_SHARED_API void b3CalculateInverseKinematicsAddTargetPurePosition(b3SharedMemoryCommandHandle commandHandle, int endEffectorLinkIndex, const double targetPosition[3]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3235,7 +3235,7 @@ void b3CalculateInverseKinematicsAddTargetPurePosition(b3SharedMemoryCommandHand } -void b3CalculateInverseKinematicsAddTargetPositionWithOrientation(b3SharedMemoryCommandHandle commandHandle, int endEffectorLinkIndex, const double targetPosition[3], const double targetOrientation[4]) +B3_SHARED_API void b3CalculateInverseKinematicsAddTargetPositionWithOrientation(b3SharedMemoryCommandHandle commandHandle, int endEffectorLinkIndex, const double targetPosition[3], const double targetOrientation[4]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3254,7 +3254,7 @@ void b3CalculateInverseKinematicsAddTargetPositionWithOrientation(b3SharedMemory } -void b3CalculateInverseKinematicsPosWithNullSpaceVel(b3SharedMemoryCommandHandle commandHandle, int numDof, int endEffectorLinkIndex, const double targetPosition[3], const double* lowerLimit, const double* upperLimit, const double* jointRange, const double* restPose) +B3_SHARED_API void b3CalculateInverseKinematicsPosWithNullSpaceVel(b3SharedMemoryCommandHandle commandHandle, int numDof, int endEffectorLinkIndex, const double targetPosition[3], const double* lowerLimit, const double* upperLimit, const double* jointRange, const double* restPose) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3275,7 +3275,7 @@ void b3CalculateInverseKinematicsPosWithNullSpaceVel(b3SharedMemoryCommandHandle } } -void b3CalculateInverseKinematicsPosOrnWithNullSpaceVel(b3SharedMemoryCommandHandle commandHandle, int numDof, int endEffectorLinkIndex, const double targetPosition[3], const double targetOrientation[4], const double* lowerLimit, const double* upperLimit, const double* jointRange, const double* restPose) +B3_SHARED_API void b3CalculateInverseKinematicsPosOrnWithNullSpaceVel(b3SharedMemoryCommandHandle commandHandle, int numDof, int endEffectorLinkIndex, const double targetPosition[3], const double targetOrientation[4], const double* lowerLimit, const double* upperLimit, const double* jointRange, const double* restPose) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3302,7 +3302,7 @@ void b3CalculateInverseKinematicsPosOrnWithNullSpaceVel(b3SharedMemoryCommandHan } -void b3CalculateInverseKinematicsSetJointDamping(b3SharedMemoryCommandHandle commandHandle, int numDof, const double* jointDampingCoeff) +B3_SHARED_API void b3CalculateInverseKinematicsSetJointDamping(b3SharedMemoryCommandHandle commandHandle, int numDof, const double* jointDampingCoeff) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3315,7 +3315,7 @@ void b3CalculateInverseKinematicsSetJointDamping(b3SharedMemoryCommandHandle com } } -int b3GetStatusInverseKinematicsJointPositions(b3SharedMemoryStatusHandle statusHandle, +B3_SHARED_API int b3GetStatusInverseKinematicsJointPositions(b3SharedMemoryStatusHandle statusHandle, int* bodyUniqueId, int* dofCount, double* jointPositions) @@ -3345,7 +3345,7 @@ int b3GetStatusInverseKinematicsJointPositions(b3SharedMemoryStatusHandle status return true; } -b3SharedMemoryCommandHandle b3RequestVREventsCommandInit(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryCommandHandle b3RequestVREventsCommandInit(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient*)physClient; b3Assert(cl); @@ -3358,7 +3358,7 @@ b3SharedMemoryCommandHandle b3RequestVREventsCommandInit(b3PhysicsClientHandle p return (b3SharedMemoryCommandHandle)command; } -void b3VREventsSetDeviceTypeFilter(b3SharedMemoryCommandHandle commandHandle, int deviceTypeFilter) +B3_SHARED_API void b3VREventsSetDeviceTypeFilter(b3SharedMemoryCommandHandle commandHandle, int deviceTypeFilter) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3368,7 +3368,7 @@ void b3VREventsSetDeviceTypeFilter(b3SharedMemoryCommandHandle commandHandle, in } } -void b3GetVREventsData(b3PhysicsClientHandle physClient, struct b3VREventsData* vrEventsData) +B3_SHARED_API void b3GetVREventsData(b3PhysicsClientHandle physClient, struct b3VREventsData* vrEventsData) { PhysicsClient* cl = (PhysicsClient* ) physClient; if (cl) @@ -3377,7 +3377,7 @@ void b3GetVREventsData(b3PhysicsClientHandle physClient, struct b3VREventsData* } } -b3SharedMemoryCommandHandle b3SetVRCameraStateCommandInit(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryCommandHandle b3SetVRCameraStateCommandInit(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient*)physClient; b3Assert(cl); @@ -3392,7 +3392,7 @@ b3SharedMemoryCommandHandle b3SetVRCameraStateCommandInit(b3PhysicsClientHandle } -int b3SetVRCameraRootPosition(b3SharedMemoryCommandHandle commandHandle, double rootPos[3]) +B3_SHARED_API int b3SetVRCameraRootPosition(b3SharedMemoryCommandHandle commandHandle, double rootPos[3]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3405,7 +3405,7 @@ int b3SetVRCameraRootPosition(b3SharedMemoryCommandHandle commandHandle, double } -int b3SetVRCameraRootOrientation(b3SharedMemoryCommandHandle commandHandle, double rootOrn[4]) +B3_SHARED_API int b3SetVRCameraRootOrientation(b3SharedMemoryCommandHandle commandHandle, double rootOrn[4]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3419,7 +3419,7 @@ int b3SetVRCameraRootOrientation(b3SharedMemoryCommandHandle commandHandle, doub return 0; } -int b3SetVRCameraTrackingObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId) +B3_SHARED_API int b3SetVRCameraTrackingObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3429,7 +3429,7 @@ int b3SetVRCameraTrackingObject(b3SharedMemoryCommandHandle commandHandle, int o return 0; } -int b3SetVRCameraTrackingObjectFlag(b3SharedMemoryCommandHandle commandHandle, int flag) +B3_SHARED_API int b3SetVRCameraTrackingObjectFlag(b3SharedMemoryCommandHandle commandHandle, int flag) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3440,7 +3440,7 @@ int b3SetVRCameraTrackingObjectFlag(b3SharedMemoryCommandHandle commandHandle, i } -b3SharedMemoryCommandHandle b3RequestKeyboardEventsCommandInit(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryCommandHandle b3RequestKeyboardEventsCommandInit(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient*)physClient; b3Assert(cl); @@ -3454,7 +3454,7 @@ b3SharedMemoryCommandHandle b3RequestKeyboardEventsCommandInit(b3PhysicsClientHa return (b3SharedMemoryCommandHandle)command; } -void b3GetKeyboardEventsData(b3PhysicsClientHandle physClient, struct b3KeyboardEventsData* keyboardEventsData) +B3_SHARED_API void b3GetKeyboardEventsData(b3PhysicsClientHandle physClient, struct b3KeyboardEventsData* keyboardEventsData) { PhysicsClient* cl = (PhysicsClient* ) physClient; if (cl) @@ -3463,7 +3463,7 @@ void b3GetKeyboardEventsData(b3PhysicsClientHandle physClient, struct b3Keyboard } } -b3SharedMemoryCommandHandle b3RequestMouseEventsCommandInit(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryCommandHandle b3RequestMouseEventsCommandInit(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient*)physClient; b3Assert(cl); @@ -3477,7 +3477,7 @@ b3SharedMemoryCommandHandle b3RequestMouseEventsCommandInit(b3PhysicsClientHandl return (b3SharedMemoryCommandHandle)command; } -void b3GetMouseEventsData(b3PhysicsClientHandle physClient, struct b3MouseEventsData* mouseEventsData) +B3_SHARED_API void b3GetMouseEventsData(b3PhysicsClientHandle physClient, struct b3MouseEventsData* mouseEventsData) { PhysicsClient* cl = (PhysicsClient* ) physClient; if (cl) @@ -3489,7 +3489,7 @@ void b3GetMouseEventsData(b3PhysicsClientHandle physClient, struct b3MouseEvents -b3SharedMemoryCommandHandle b3ProfileTimingCommandInit(b3PhysicsClientHandle physClient, const char* name) +B3_SHARED_API b3SharedMemoryCommandHandle b3ProfileTimingCommandInit(b3PhysicsClientHandle physClient, const char* name) { PhysicsClient* cl = (PhysicsClient*)physClient; b3Assert(cl); @@ -3514,7 +3514,7 @@ b3SharedMemoryCommandHandle b3ProfileTimingCommandInit(b3PhysicsClientHandle phy return (b3SharedMemoryCommandHandle)command; } -void b3SetProfileTimingDuractionInMicroSeconds(b3SharedMemoryCommandHandle commandHandle, int duration) +B3_SHARED_API void b3SetProfileTimingDuractionInMicroSeconds(b3SharedMemoryCommandHandle commandHandle, int duration) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3525,7 +3525,7 @@ void b3SetProfileTimingDuractionInMicroSeconds(b3SharedMemoryCommandHandle comma } } -b3SharedMemoryCommandHandle b3StateLoggingCommandInit(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryCommandHandle b3StateLoggingCommandInit(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient*)physClient; b3Assert(cl); @@ -3542,7 +3542,7 @@ b3SharedMemoryCommandHandle b3StateLoggingCommandInit(b3PhysicsClientHandle phys } -int b3StateLoggingStart(b3SharedMemoryCommandHandle commandHandle, int loggingType, const char* fileName) +B3_SHARED_API int b3StateLoggingStart(b3SharedMemoryCommandHandle commandHandle, int loggingType, const char* fileName) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3564,7 +3564,7 @@ int b3StateLoggingStart(b3SharedMemoryCommandHandle commandHandle, int loggingTy return 0; } -int b3GetStatusLoggingUniqueId(b3SharedMemoryStatusHandle statusHandle) +B3_SHARED_API int b3GetStatusLoggingUniqueId(b3SharedMemoryStatusHandle statusHandle) { const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle; b3Assert(status); @@ -3576,7 +3576,7 @@ int b3GetStatusLoggingUniqueId(b3SharedMemoryStatusHandle statusHandle) return -1; } -int b3StateLoggingAddLoggingObjectUniqueId(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId) +B3_SHARED_API int b3StateLoggingAddLoggingObjectUniqueId(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3592,7 +3592,7 @@ int b3StateLoggingAddLoggingObjectUniqueId(b3SharedMemoryCommandHandle commandHa return 0; } -int b3StateLoggingSetLinkIndexA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA) +B3_SHARED_API int b3StateLoggingSetLinkIndexA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3605,7 +3605,7 @@ int b3StateLoggingSetLinkIndexA(b3SharedMemoryCommandHandle commandHandle, int l return 0; } -int b3StateLoggingSetLinkIndexB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB) +B3_SHARED_API int b3StateLoggingSetLinkIndexB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3618,7 +3618,7 @@ int b3StateLoggingSetLinkIndexB(b3SharedMemoryCommandHandle commandHandle, int l return 0; } -int b3StateLoggingSetBodyAUniqueId(b3SharedMemoryCommandHandle commandHandle, int bodyAUniqueId) +B3_SHARED_API int b3StateLoggingSetBodyAUniqueId(b3SharedMemoryCommandHandle commandHandle, int bodyAUniqueId) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3631,7 +3631,7 @@ int b3StateLoggingSetBodyAUniqueId(b3SharedMemoryCommandHandle commandHandle, in return 0; } -int b3StateLoggingSetBodyBUniqueId(b3SharedMemoryCommandHandle commandHandle, int bodyBUniqueId) +B3_SHARED_API int b3StateLoggingSetBodyBUniqueId(b3SharedMemoryCommandHandle commandHandle, int bodyBUniqueId) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3644,7 +3644,7 @@ int b3StateLoggingSetBodyBUniqueId(b3SharedMemoryCommandHandle commandHandle, in return 0; } -int b3StateLoggingSetMaxLogDof(b3SharedMemoryCommandHandle commandHandle, int maxLogDof) +B3_SHARED_API int b3StateLoggingSetMaxLogDof(b3SharedMemoryCommandHandle commandHandle, int maxLogDof) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3657,7 +3657,7 @@ int b3StateLoggingSetMaxLogDof(b3SharedMemoryCommandHandle commandHandle, int ma return 0; } -int b3StateLoggingSetLogFlags(b3SharedMemoryCommandHandle commandHandle, int logFlags) +B3_SHARED_API int b3StateLoggingSetLogFlags(b3SharedMemoryCommandHandle commandHandle, int logFlags) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3673,7 +3673,7 @@ int b3StateLoggingSetLogFlags(b3SharedMemoryCommandHandle commandHandle, int log -int b3StateLoggingSetDeviceTypeFilter(b3SharedMemoryCommandHandle commandHandle, int deviceTypeFilter) +B3_SHARED_API int b3StateLoggingSetDeviceTypeFilter(b3SharedMemoryCommandHandle commandHandle, int deviceTypeFilter) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3686,7 +3686,7 @@ int b3StateLoggingSetDeviceTypeFilter(b3SharedMemoryCommandHandle commandHandle, return 0; } -int b3StateLoggingStop(b3SharedMemoryCommandHandle commandHandle, int loggingUid) +B3_SHARED_API int b3StateLoggingStop(b3SharedMemoryCommandHandle commandHandle, int loggingUid) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3701,7 +3701,7 @@ int b3StateLoggingStop(b3SharedMemoryCommandHandle commandHandle, int loggingUid ///configure the 3D OpenGL debug visualizer (enable/disable GUI widgets, shadows, position camera etc) -b3SharedMemoryCommandHandle b3InitConfigureOpenGLVisualizer(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitConfigureOpenGLVisualizer(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient*)physClient; b3Assert(cl); @@ -3715,7 +3715,7 @@ b3SharedMemoryCommandHandle b3InitConfigureOpenGLVisualizer(b3PhysicsClientHandl return (b3SharedMemoryCommandHandle)command; } -void b3ConfigureOpenGLVisualizerSetVisualizationFlags(b3SharedMemoryCommandHandle commandHandle, int flag, int enabled) +B3_SHARED_API void b3ConfigureOpenGLVisualizerSetVisualizationFlags(b3SharedMemoryCommandHandle commandHandle, int flag, int enabled) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3728,7 +3728,7 @@ void b3ConfigureOpenGLVisualizerSetVisualizationFlags(b3SharedMemoryCommandHandl } } -void b3ConfigureOpenGLVisualizerSetViewMatrix(b3SharedMemoryCommandHandle commandHandle, float cameraDistance, float cameraPitch, float cameraYaw, const float cameraTargetPosition[3]) +B3_SHARED_API void b3ConfigureOpenGLVisualizerSetViewMatrix(b3SharedMemoryCommandHandle commandHandle, float cameraDistance, float cameraPitch, float cameraYaw, const float cameraTargetPosition[3]) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); @@ -3746,7 +3746,7 @@ void b3ConfigureOpenGLVisualizerSetViewMatrix(b3SharedMemoryCommandHandle comman } } -b3SharedMemoryCommandHandle b3InitRequestOpenGLVisualizerCameraCommand(b3PhysicsClientHandle physClient) +B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestOpenGLVisualizerCameraCommand(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient*)physClient; b3Assert(cl); @@ -3761,7 +3761,7 @@ b3SharedMemoryCommandHandle b3InitRequestOpenGLVisualizerCameraCommand(b3Physics } -int b3GetStatusOpenGLVisualizerCamera(b3SharedMemoryStatusHandle statusHandle, b3OpenGLVisualizerCameraInfo* camera) +B3_SHARED_API int b3GetStatusOpenGLVisualizerCamera(b3SharedMemoryStatusHandle statusHandle, b3OpenGLVisualizerCameraInfo* camera) { const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle; //b3Assert(status); @@ -3773,7 +3773,7 @@ int b3GetStatusOpenGLVisualizerCamera(b3SharedMemoryStatusHandle statusHandle, b return 0; } -void b3SetTimeOut(b3PhysicsClientHandle physClient, double timeOutInSeconds) +B3_SHARED_API void b3SetTimeOut(b3PhysicsClientHandle physClient, double timeOutInSeconds) { PhysicsClient* cl = (PhysicsClient*)physClient; b3Assert(cl); @@ -3785,7 +3785,7 @@ void b3SetTimeOut(b3PhysicsClientHandle physClient, double timeOutInSeconds) } -double b3GetTimeOut(b3PhysicsClientHandle physClient) +B3_SHARED_API double b3GetTimeOut(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient*)physClient; b3Assert(cl); @@ -3796,7 +3796,7 @@ double b3GetTimeOut(b3PhysicsClientHandle physClient) return -1; } -b3SharedMemoryCommandHandle b3SetAdditionalSearchPath(b3PhysicsClientHandle physClient, char* path) +B3_SHARED_API b3SharedMemoryCommandHandle b3SetAdditionalSearchPath(b3PhysicsClientHandle physClient, char* path) { PhysicsClient* cl = (PhysicsClient*)physClient; b3Assert(cl); @@ -3815,7 +3815,7 @@ b3SharedMemoryCommandHandle b3SetAdditionalSearchPath(b3PhysicsClientHandle phys } -void b3MultiplyTransforms(const double posA[3], const double ornA[4], const double posB[3], const double ornB[4], double outPos[3], double outOrn[4]) +B3_SHARED_API void b3MultiplyTransforms(const double posA[3], const double ornA[4], const double posB[3], const double ornB[4], double outPos[3], double outOrn[4]) { b3Transform trA; b3Transform trB; @@ -3834,7 +3834,7 @@ void b3MultiplyTransforms(const double posA[3], const double ornA[4], const doub outOrn[3] = orn[3]; } -void b3InvertTransform(const double pos[3], const double orn[4], double outPos[3], double outOrn[4]) +B3_SHARED_API void b3InvertTransform(const double pos[3], const double orn[4], double outPos[3], double outOrn[4]) { b3Transform tr; tr.setOrigin(b3MakeVector3(pos[0],pos[1],pos[2])); diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index 04105e701..af297ea68 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -10,6 +10,14 @@ B3_DECLARE_HANDLE(b3PhysicsClientHandle); B3_DECLARE_HANDLE(b3SharedMemoryCommandHandle); B3_DECLARE_HANDLE(b3SharedMemoryStatusHandle); +#ifdef _WIN32 + #define B3_SHARED_API __declspec(dllexport) +#elif defined (__GNUC__) + #define B3_SHARED_API __attribute__((visibility("default"))) +#else + #define B3_SHARED_API +#endif + ///There are several connection methods, see following header files: #include "PhysicsClientSharedMemory_C_API.h" @@ -33,30 +41,30 @@ extern "C" { ///b3DisconnectSharedMemory will disconnect the client from the server and cleanup memory. -void b3DisconnectSharedMemory(b3PhysicsClientHandle physClient); +B3_SHARED_API void b3DisconnectSharedMemory(b3PhysicsClientHandle physClient); ///There can only be 1 outstanding command. Check if a command can be send. -int b3CanSubmitCommand(b3PhysicsClientHandle physClient); +B3_SHARED_API int b3CanSubmitCommand(b3PhysicsClientHandle physClient); ///blocking submit command and wait for status -b3SharedMemoryStatusHandle b3SubmitClientCommandAndWaitStatus(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle); +B3_SHARED_API b3SharedMemoryStatusHandle b3SubmitClientCommandAndWaitStatus(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle); ///In general it is better to use b3SubmitClientCommandAndWaitStatus. b3SubmitClientCommand is a non-blocking submit ///command, which requires checking for the status manually, using b3ProcessServerStatus. Also, before sending the ///next command, make sure to check if you can send a command using 'b3CanSubmitCommand'. -int b3SubmitClientCommand(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle); +B3_SHARED_API int b3SubmitClientCommand(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle); ///non-blocking check status -b3SharedMemoryStatusHandle b3ProcessServerStatus(b3PhysicsClientHandle physClient); +B3_SHARED_API b3SharedMemoryStatusHandle b3ProcessServerStatus(b3PhysicsClientHandle physClient); /// Get the physics server return status type. See EnumSharedMemoryServerStatus in SharedMemoryPublic.h for error codes. -int b3GetStatusType(b3SharedMemoryStatusHandle statusHandle); +B3_SHARED_API int b3GetStatusType(b3SharedMemoryStatusHandle statusHandle); -int b3GetStatusBodyIndices(b3SharedMemoryStatusHandle statusHandle, int* bodyIndicesOut, int bodyIndicesCapacity); +B3_SHARED_API int b3GetStatusBodyIndices(b3SharedMemoryStatusHandle statusHandle, int* bodyIndicesOut, int bodyIndicesCapacity); -int b3GetStatusBodyIndex(b3SharedMemoryStatusHandle statusHandle); +B3_SHARED_API int b3GetStatusBodyIndex(b3SharedMemoryStatusHandle statusHandle); -int b3GetStatusActualState(b3SharedMemoryStatusHandle statusHandle, +B3_SHARED_API int b3GetStatusActualState(b3SharedMemoryStatusHandle statusHandle, int* bodyUniqueId, int* numDegreeOfFreedomQ, int* numDegreeOfFreedomU, @@ -66,315 +74,315 @@ int b3GetStatusActualState(b3SharedMemoryStatusHandle statusHandle, const double* jointReactionForces[]); -b3SharedMemoryCommandHandle b3RequestCollisionInfoCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId); -int b3GetStatusAABB(b3SharedMemoryStatusHandle statusHandle, int linkIndex, double aabbMin[3], double aabbMax[3]); +B3_SHARED_API b3SharedMemoryCommandHandle b3RequestCollisionInfoCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId); +B3_SHARED_API int b3GetStatusAABB(b3SharedMemoryStatusHandle statusHandle, int linkIndex, double aabbMin[/*3*/], double aabbMax[/*3*/]); ///If you re-connected to an existing server, or server changed otherwise, sync the body info and user constraints etc. -b3SharedMemoryCommandHandle b3InitSyncBodyInfoCommand(b3PhysicsClientHandle physClient); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitSyncBodyInfoCommand(b3PhysicsClientHandle physClient); -b3SharedMemoryCommandHandle b3InitRemoveBodyCommand(b3PhysicsClientHandle physClient, int bodyUniqueId); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitRemoveBodyCommand(b3PhysicsClientHandle physClient, int bodyUniqueId); ///return the total number of bodies in the simulation -int b3GetNumBodies(b3PhysicsClientHandle physClient); +B3_SHARED_API int b3GetNumBodies(b3PhysicsClientHandle physClient); /// return the body unique id, given the index in range [0 , b3GetNumBodies() ) -int b3GetBodyUniqueId(b3PhysicsClientHandle physClient, int serialIndex); +B3_SHARED_API int b3GetBodyUniqueId(b3PhysicsClientHandle physClient, int serialIndex); ///given a body unique id, return the body information. See b3BodyInfo in SharedMemoryPublic.h -int b3GetBodyInfo(b3PhysicsClientHandle physClient, int bodyUniqueId, struct b3BodyInfo* info); +B3_SHARED_API int b3GetBodyInfo(b3PhysicsClientHandle physClient, int bodyUniqueId, struct b3BodyInfo* info); ///give a unique body index (after loading the body) return the number of joints. -int b3GetNumJoints(b3PhysicsClientHandle physClient, int bodyIndex); +B3_SHARED_API int b3GetNumJoints(b3PhysicsClientHandle physClient, int bodyIndex); ///given a body and joint index, return the joint information. See b3JointInfo in SharedMemoryPublic.h -int b3GetJointInfo(b3PhysicsClientHandle physClient, int bodyIndex, int jointIndex, struct b3JointInfo* info); +B3_SHARED_API int b3GetJointInfo(b3PhysicsClientHandle physClient, int bodyIndex, int jointIndex, struct b3JointInfo* info); -b3SharedMemoryCommandHandle b3GetDynamicsInfoCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, int linkIndex); +B3_SHARED_API b3SharedMemoryCommandHandle b3GetDynamicsInfoCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, int linkIndex); ///given a body unique id and link index, return the dynamics information. See b3DynamicsInfo in SharedMemoryPublic.h -int b3GetDynamicsInfo(b3SharedMemoryStatusHandle statusHandle, struct b3DynamicsInfo* info); +B3_SHARED_API int b3GetDynamicsInfo(b3SharedMemoryStatusHandle statusHandle, struct b3DynamicsInfo* info); -b3SharedMemoryCommandHandle b3InitChangeDynamicsInfo(b3PhysicsClientHandle physClient); -int b3ChangeDynamicsInfoSetMass(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double mass); -int b3ChangeDynamicsInfoSetLateralFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double lateralFriction); -int b3ChangeDynamicsInfoSetSpinningFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double friction); -int b3ChangeDynamicsInfoSetRollingFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double friction); -int b3ChangeDynamicsInfoSetRestitution(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double restitution); -int b3ChangeDynamicsInfoSetLinearDamping(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId,double linearDamping); -int b3ChangeDynamicsInfoSetAngularDamping(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId,double angularDamping); -int b3ChangeDynamicsInfoSetContactStiffnessAndDamping(b3SharedMemoryCommandHandle commandHandle,int bodyUniqueId,int linkIndex,double contactStiffness, double contactDamping); -int b3ChangeDynamicsInfoSetFrictionAnchor(b3SharedMemoryCommandHandle commandHandle,int bodyUniqueId,int linkIndex, int frictionAnchor); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitChangeDynamicsInfo(b3PhysicsClientHandle physClient); +B3_SHARED_API int b3ChangeDynamicsInfoSetMass(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double mass); +B3_SHARED_API int b3ChangeDynamicsInfoSetLateralFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double lateralFriction); +B3_SHARED_API int b3ChangeDynamicsInfoSetSpinningFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double friction); +B3_SHARED_API int b3ChangeDynamicsInfoSetRollingFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double friction); +B3_SHARED_API int b3ChangeDynamicsInfoSetRestitution(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double restitution); +B3_SHARED_API int b3ChangeDynamicsInfoSetLinearDamping(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId,double linearDamping); +B3_SHARED_API int b3ChangeDynamicsInfoSetAngularDamping(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId,double angularDamping); +B3_SHARED_API int b3ChangeDynamicsInfoSetContactStiffnessAndDamping(b3SharedMemoryCommandHandle commandHandle,int bodyUniqueId,int linkIndex,double contactStiffness, double contactDamping); +B3_SHARED_API int b3ChangeDynamicsInfoSetFrictionAnchor(b3SharedMemoryCommandHandle commandHandle,int bodyUniqueId,int linkIndex, int frictionAnchor); -b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand(b3PhysicsClientHandle physClient, int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, struct b3JointInfo* info); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand(b3PhysicsClientHandle physClient, int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, struct b3JointInfo* info); ///return a unique id for the user constraint, after successful creation, or -1 for an invalid constraint id -int b3GetStatusUserConstraintUniqueId(b3SharedMemoryStatusHandle statusHandle); +B3_SHARED_API int b3GetStatusUserConstraintUniqueId(b3SharedMemoryStatusHandle statusHandle); ///change parameters of an existing user constraint -b3SharedMemoryCommandHandle b3InitChangeUserConstraintCommand(b3PhysicsClientHandle physClient, int userConstraintUniqueId); -int b3InitChangeUserConstraintSetPivotInB(b3SharedMemoryCommandHandle commandHandle, double jointChildPivot[3]); -int b3InitChangeUserConstraintSetFrameInB(b3SharedMemoryCommandHandle commandHandle, double jointChildFrameOrn[4]); -int b3InitChangeUserConstraintSetMaxForce(b3SharedMemoryCommandHandle commandHandle, double maxAppliedForce); -int b3InitChangeUserConstraintSetGearRatio(b3SharedMemoryCommandHandle commandHandle, double gearRatio); -int b3InitChangeUserConstraintSetGearAuxLink(b3SharedMemoryCommandHandle commandHandle, int gearAuxLink); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitChangeUserConstraintCommand(b3PhysicsClientHandle physClient, int userConstraintUniqueId); +B3_SHARED_API int b3InitChangeUserConstraintSetPivotInB(b3SharedMemoryCommandHandle commandHandle, double jointChildPivot[/*3*/]); +B3_SHARED_API int b3InitChangeUserConstraintSetFrameInB(b3SharedMemoryCommandHandle commandHandle, double jointChildFrameOrn[/*4*/]); +B3_SHARED_API int b3InitChangeUserConstraintSetMaxForce(b3SharedMemoryCommandHandle commandHandle, double maxAppliedForce); +B3_SHARED_API int b3InitChangeUserConstraintSetGearRatio(b3SharedMemoryCommandHandle commandHandle, double gearRatio); +B3_SHARED_API int b3InitChangeUserConstraintSetGearAuxLink(b3SharedMemoryCommandHandle commandHandle, int gearAuxLink); -b3SharedMemoryCommandHandle b3InitRemoveUserConstraintCommand(b3PhysicsClientHandle physClient, int userConstraintUniqueId); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitRemoveUserConstraintCommand(b3PhysicsClientHandle physClient, int userConstraintUniqueId); -int b3GetNumUserConstraints(b3PhysicsClientHandle physClient); -int b3GetUserConstraintInfo(b3PhysicsClientHandle physClient, int constraintUniqueId, struct b3UserConstraint* info); +B3_SHARED_API int b3GetNumUserConstraints(b3PhysicsClientHandle physClient); +B3_SHARED_API int b3GetUserConstraintInfo(b3PhysicsClientHandle physClient, int constraintUniqueId, struct b3UserConstraint* info); /// return the user constraint id, given the index in range [0 , b3GetNumUserConstraints() ) -int b3GetUserConstraintId(b3PhysicsClientHandle physClient, int serialIndex); +B3_SHARED_API int b3GetUserConstraintId(b3PhysicsClientHandle physClient, int serialIndex); ///Request physics debug lines for debug visualization. The flags in debugMode are the same as used in Bullet ///See btIDebugDraw::DebugDrawModes in Bullet/src/LinearMath/btIDebugDraw.h -b3SharedMemoryCommandHandle b3InitRequestDebugLinesCommand(b3PhysicsClientHandle physClient, int debugMode); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestDebugLinesCommand(b3PhysicsClientHandle physClient, int debugMode); ///Get the pointers to the physics debug line information, after b3InitRequestDebugLinesCommand returns ///status CMD_DEBUG_LINES_COMPLETED -void b3GetDebugLines(b3PhysicsClientHandle physClient, struct b3DebugLines* lines); +B3_SHARED_API void b3GetDebugLines(b3PhysicsClientHandle physClient, struct b3DebugLines* lines); ///configure the 3D OpenGL debug visualizer (enable/disable GUI widgets, shadows, position camera etc) -b3SharedMemoryCommandHandle b3InitConfigureOpenGLVisualizer(b3PhysicsClientHandle physClient); -void b3ConfigureOpenGLVisualizerSetVisualizationFlags(b3SharedMemoryCommandHandle commandHandle, int flag, int enabled); -void b3ConfigureOpenGLVisualizerSetViewMatrix(b3SharedMemoryCommandHandle commandHandle, float cameraDistance, float cameraPitch, float cameraYaw, const float cameraTargetPosition[3]); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitConfigureOpenGLVisualizer(b3PhysicsClientHandle physClient); +B3_SHARED_API void b3ConfigureOpenGLVisualizerSetVisualizationFlags(b3SharedMemoryCommandHandle commandHandle, int flag, int enabled); +B3_SHARED_API void b3ConfigureOpenGLVisualizerSetViewMatrix(b3SharedMemoryCommandHandle commandHandle, float cameraDistance, float cameraPitch, float cameraYaw, const float cameraTargetPosition[/*3*/]); -b3SharedMemoryCommandHandle b3InitRequestOpenGLVisualizerCameraCommand(b3PhysicsClientHandle physClient); -int b3GetStatusOpenGLVisualizerCamera(b3SharedMemoryStatusHandle statusHandle, struct b3OpenGLVisualizerCameraInfo* camera); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestOpenGLVisualizerCameraCommand(b3PhysicsClientHandle physClient); +B3_SHARED_API int b3GetStatusOpenGLVisualizerCamera(b3SharedMemoryStatusHandle statusHandle, struct b3OpenGLVisualizerCameraInfo* camera); /// Add/remove user-specific debug lines and debug text messages -b3SharedMemoryCommandHandle b3InitUserDebugDrawAddLine3D(b3PhysicsClientHandle physClient, double fromXYZ[3], double toXYZ[3], double colorRGB[3], double lineWidth, double lifeTime); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawAddLine3D(b3PhysicsClientHandle physClient, double fromXYZ[/*3*/], double toXYZ[/*3*/], double colorRGB[/*3*/], double lineWidth, double lifeTime); -b3SharedMemoryCommandHandle b3InitUserDebugDrawAddText3D(b3PhysicsClientHandle physClient, const char* txt, double positionXYZ[3], double colorRGB[3], double textSize, double lifeTime); -void b3UserDebugTextSetOptionFlags(b3SharedMemoryCommandHandle commandHandle, int optionFlags); -void b3UserDebugTextSetOrientation(b3SharedMemoryCommandHandle commandHandle, double orientation[4]); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawAddText3D(b3PhysicsClientHandle physClient, const char* txt, double positionXYZ[/*3*/], double colorRGB[/*3*/], double textSize, double lifeTime); +B3_SHARED_API void b3UserDebugTextSetOptionFlags(b3SharedMemoryCommandHandle commandHandle, int optionFlags); +B3_SHARED_API void b3UserDebugTextSetOrientation(b3SharedMemoryCommandHandle commandHandle, double orientation[/*4*/]); -void b3UserDebugItemSetParentObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex); +B3_SHARED_API void b3UserDebugItemSetParentObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex); -b3SharedMemoryCommandHandle b3InitUserDebugAddParameter(b3PhysicsClientHandle physClient, const char* txt, double rangeMin, double rangeMax, double startValue); -b3SharedMemoryCommandHandle b3InitUserDebugReadParameter(b3PhysicsClientHandle physClient, int debugItemUniqueId); -int b3GetStatusDebugParameterValue(b3SharedMemoryStatusHandle statusHandle, double* paramValue); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugAddParameter(b3PhysicsClientHandle physClient, const char* txt, double rangeMin, double rangeMax, double startValue); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugReadParameter(b3PhysicsClientHandle physClient, int debugItemUniqueId); +B3_SHARED_API int b3GetStatusDebugParameterValue(b3SharedMemoryStatusHandle statusHandle, double* paramValue); -b3SharedMemoryCommandHandle b3InitUserDebugDrawRemove(b3PhysicsClientHandle physClient, int debugItemUniqueId); -b3SharedMemoryCommandHandle b3InitUserDebugDrawRemoveAll(b3PhysicsClientHandle physClient); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawRemove(b3PhysicsClientHandle physClient, int debugItemUniqueId); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawRemoveAll(b3PhysicsClientHandle physClient); -b3SharedMemoryCommandHandle b3InitDebugDrawingCommand(b3PhysicsClientHandle physClient); -void b3SetDebugObjectColor(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex, double objectColorRGB[3]); -void b3RemoveDebugObjectColor(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitDebugDrawingCommand(b3PhysicsClientHandle physClient); +B3_SHARED_API void b3SetDebugObjectColor(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex, double objectColorRGB[/*3*/]); +B3_SHARED_API void b3RemoveDebugObjectColor(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex); ///All debug items unique Ids are positive: a negative unique Id means failure. -int b3GetDebugItemUniqueId(b3SharedMemoryStatusHandle statusHandle); +B3_SHARED_API int b3GetDebugItemUniqueId(b3SharedMemoryStatusHandle statusHandle); ///request an image from a simulated camera, using a software renderer. -b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physClient); -void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle command, float viewMatrix[16], float projectionMatrix[16]); -void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle command, int width, int height ); -void b3RequestCameraImageSetLightDirection(b3SharedMemoryCommandHandle commandHandle, const float lightDirection[3]); -void b3RequestCameraImageSetLightColor(b3SharedMemoryCommandHandle commandHandle, const float lightColor[3]); -void b3RequestCameraImageSetLightDistance(b3SharedMemoryCommandHandle commandHandle, float lightDistance); -void b3RequestCameraImageSetLightAmbientCoeff(b3SharedMemoryCommandHandle commandHandle, float lightAmbientCoeff); -void b3RequestCameraImageSetLightDiffuseCoeff(b3SharedMemoryCommandHandle commandHandle, float lightDiffuseCoeff); -void b3RequestCameraImageSetLightSpecularCoeff(b3SharedMemoryCommandHandle commandHandle, float lightSpecularCoeff); -void b3RequestCameraImageSetShadow(b3SharedMemoryCommandHandle commandHandle, int hasShadow); -void b3RequestCameraImageSelectRenderer(b3SharedMemoryCommandHandle commandHandle, int renderer); -void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physClient); +B3_SHARED_API void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle command, float viewMatrix[/*16*/], float projectionMatrix[/*16*/]); +B3_SHARED_API void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle command, int width, int height ); +B3_SHARED_API void b3RequestCameraImageSetLightDirection(b3SharedMemoryCommandHandle commandHandle, const float lightDirection[/*3*/]); +B3_SHARED_API void b3RequestCameraImageSetLightColor(b3SharedMemoryCommandHandle commandHandle, const float lightColor[/*3*/]); +B3_SHARED_API void b3RequestCameraImageSetLightDistance(b3SharedMemoryCommandHandle commandHandle, float lightDistance); +B3_SHARED_API void b3RequestCameraImageSetLightAmbientCoeff(b3SharedMemoryCommandHandle commandHandle, float lightAmbientCoeff); +B3_SHARED_API void b3RequestCameraImageSetLightDiffuseCoeff(b3SharedMemoryCommandHandle commandHandle, float lightDiffuseCoeff); +B3_SHARED_API void b3RequestCameraImageSetLightSpecularCoeff(b3SharedMemoryCommandHandle commandHandle, float lightSpecularCoeff); +B3_SHARED_API void b3RequestCameraImageSetShadow(b3SharedMemoryCommandHandle commandHandle, int hasShadow); +B3_SHARED_API void b3RequestCameraImageSelectRenderer(b3SharedMemoryCommandHandle commandHandle, int renderer); +B3_SHARED_API void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData); ///compute a view matrix, helper function for b3RequestCameraImageSetCameraMatrices -void b3ComputeViewMatrixFromPositions(const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3], float viewMatrix[16]); -void b3ComputeViewMatrixFromYawPitchRoll(const float cameraTargetPosition[3], float distance, float yaw, float pitch, float roll, int upAxis, float viewMatrix[16]); -void b3ComputePositionFromViewMatrix(const float viewMatrix[16], float cameraPosition[3], float cameraTargetPosition[3], float cameraUp[3]); +B3_SHARED_API void b3ComputeViewMatrixFromPositions(const float cameraPosition[/*3*/], const float cameraTargetPosition[/*3*/], const float cameraUp[/*3*/], float viewMatrix[/*16*/]); +B3_SHARED_API void b3ComputeViewMatrixFromYawPitchRoll(const float cameraTargetPosition[/*3*/], float distance, float yaw, float pitch, float roll, int upAxis, float viewMatrix[/*16*/]); +B3_SHARED_API void b3ComputePositionFromViewMatrix(const float viewMatrix[/*16*/], float cameraPosition[/*3*/], float cameraTargetPosition[/*3*/], float cameraUp[/*3*/]); ///compute a projection matrix, helper function for b3RequestCameraImageSetCameraMatrices -void b3ComputeProjectionMatrix(float left, float right, float bottom, float top, float nearVal, float farVal, float projectionMatrix[16]); -void b3ComputeProjectionMatrixFOV(float fov, float aspect, float nearVal, float farVal, float projectionMatrix[16]); +B3_SHARED_API void b3ComputeProjectionMatrix(float left, float right, float bottom, float top, float nearVal, float farVal, float projectionMatrix[/*16*/]); +B3_SHARED_API void b3ComputeProjectionMatrixFOV(float fov, float aspect, float nearVal, float farVal, float projectionMatrix[/*16*/]); /* obsolete, please use b3ComputeViewProjectionMatrices */ -void b3RequestCameraImageSetViewMatrix(b3SharedMemoryCommandHandle command, const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3]); +B3_SHARED_API void b3RequestCameraImageSetViewMatrix(b3SharedMemoryCommandHandle command, const float cameraPosition[/*3*/], const float cameraTargetPosition[/*3*/], const float cameraUp[/*3*/]); /* obsolete, please use b3ComputeViewProjectionMatrices */ -void b3RequestCameraImageSetViewMatrix2(b3SharedMemoryCommandHandle commandHandle, const float cameraTargetPosition[3], float distance, float yaw, float pitch, float roll, int upAxis); +B3_SHARED_API void b3RequestCameraImageSetViewMatrix2(b3SharedMemoryCommandHandle commandHandle, const float cameraTargetPosition[/*3*/], float distance, float yaw, float pitch, float roll, int upAxis); /* obsolete, please use b3ComputeViewProjectionMatrices */ -void b3RequestCameraImageSetProjectionMatrix(b3SharedMemoryCommandHandle command, float left, float right, float bottom, float top, float nearVal, float farVal); +B3_SHARED_API void b3RequestCameraImageSetProjectionMatrix(b3SharedMemoryCommandHandle command, float left, float right, float bottom, float top, float nearVal, float farVal); /* obsolete, please use b3ComputeViewProjectionMatrices */ -void b3RequestCameraImageSetFOVProjectionMatrix(b3SharedMemoryCommandHandle command, float fov, float aspect, float nearVal, float farVal); +B3_SHARED_API void b3RequestCameraImageSetFOVProjectionMatrix(b3SharedMemoryCommandHandle command, float fov, float aspect, float nearVal, float farVal); ///request an contact point information -b3SharedMemoryCommandHandle b3InitRequestContactPointInformation(b3PhysicsClientHandle physClient); -void b3SetContactFilterBodyA(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdA); -void b3SetContactFilterBodyB(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdB); -void b3SetContactFilterLinkA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA); -void b3SetContactFilterLinkB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB); -void b3GetContactPointInformation(b3PhysicsClientHandle physClient, struct b3ContactInformation* contactPointInfo); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestContactPointInformation(b3PhysicsClientHandle physClient); +B3_SHARED_API void b3SetContactFilterBodyA(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdA); +B3_SHARED_API void b3SetContactFilterBodyB(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdB); +B3_SHARED_API void b3SetContactFilterLinkA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA); +B3_SHARED_API void b3SetContactFilterLinkB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB); +B3_SHARED_API void b3GetContactPointInformation(b3PhysicsClientHandle physClient, struct b3ContactInformation* contactPointInfo); ///compute the closest points between two bodies -b3SharedMemoryCommandHandle b3InitClosestDistanceQuery(b3PhysicsClientHandle physClient); -void b3SetClosestDistanceFilterBodyA(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdA); -void b3SetClosestDistanceFilterLinkA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA); -void b3SetClosestDistanceFilterBodyB(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdB); -void b3SetClosestDistanceFilterLinkB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB); -void b3SetClosestDistanceThreshold(b3SharedMemoryCommandHandle commandHandle, double distance); -void b3GetClosestPointInformation(b3PhysicsClientHandle physClient, struct b3ContactInformation* contactPointInfo); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitClosestDistanceQuery(b3PhysicsClientHandle physClient); +B3_SHARED_API void b3SetClosestDistanceFilterBodyA(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdA); +B3_SHARED_API void b3SetClosestDistanceFilterLinkA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA); +B3_SHARED_API void b3SetClosestDistanceFilterBodyB(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdB); +B3_SHARED_API void b3SetClosestDistanceFilterLinkB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB); +B3_SHARED_API void b3SetClosestDistanceThreshold(b3SharedMemoryCommandHandle commandHandle, double distance); +B3_SHARED_API void b3GetClosestPointInformation(b3PhysicsClientHandle physClient, struct b3ContactInformation* contactPointInfo); ///get all the bodies that touch a given axis aligned bounding box specified in world space (min and max coordinates) -b3SharedMemoryCommandHandle b3InitAABBOverlapQuery(b3PhysicsClientHandle physClient, const double aabbMin[3],const double aabbMax[3]); -void b3GetAABBOverlapResults(b3PhysicsClientHandle physClient, struct b3AABBOverlapData* data); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitAABBOverlapQuery(b3PhysicsClientHandle physClient, const double aabbMin[/*3*/],const double aabbMax[/*3*/]); +B3_SHARED_API void b3GetAABBOverlapResults(b3PhysicsClientHandle physClient, struct b3AABBOverlapData* data); //request visual shape information -b3SharedMemoryCommandHandle b3InitRequestVisualShapeInformation(b3PhysicsClientHandle physClient, int bodyUniqueIdA); -void b3GetVisualShapeInformation(b3PhysicsClientHandle physClient, struct b3VisualShapeInformation* visualShapeInfo); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestVisualShapeInformation(b3PhysicsClientHandle physClient, int bodyUniqueIdA); +B3_SHARED_API void b3GetVisualShapeInformation(b3PhysicsClientHandle physClient, struct b3VisualShapeInformation* visualShapeInfo); -b3SharedMemoryCommandHandle b3InitLoadTexture(b3PhysicsClientHandle physClient, const char* filename); -int b3GetStatusTextureUniqueId(b3SharedMemoryStatusHandle statusHandle); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitLoadTexture(b3PhysicsClientHandle physClient, const char* filename); +B3_SHARED_API int b3GetStatusTextureUniqueId(b3SharedMemoryStatusHandle statusHandle); -b3SharedMemoryCommandHandle b3CreateChangeTextureCommandInit(b3PhysicsClientHandle physClient, int textureUniqueId, int width, int height, const char* rgbPixels); +B3_SHARED_API b3SharedMemoryCommandHandle b3CreateChangeTextureCommandInit(b3PhysicsClientHandle physClient, int textureUniqueId, int width, int height, const char* rgbPixels); -b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient, int bodyUniqueId, int jointIndex, int shapeIndex, int textureUniqueId); -void b3UpdateVisualShapeRGBAColor(b3SharedMemoryCommandHandle commandHandle, double rgbaColor[4]); -void b3UpdateVisualShapeSpecularColor(b3SharedMemoryCommandHandle commandHandle, double specularColor[3]); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient, int bodyUniqueId, int jointIndex, int shapeIndex, int textureUniqueId); +B3_SHARED_API void b3UpdateVisualShapeRGBAColor(b3SharedMemoryCommandHandle commandHandle, double rgbaColor[/*4*/]); +B3_SHARED_API void b3UpdateVisualShapeSpecularColor(b3SharedMemoryCommandHandle commandHandle, double specularColor[/*3*/]); -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 b3PhysicsParamSetDefaultNonContactERP(b3SharedMemoryCommandHandle commandHandle, double defaultNonContactERP); -int b3PhysicsParamSetDefaultFrictionERP(b3SharedMemoryCommandHandle commandHandle, double frictionERP); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient); +B3_SHARED_API int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, double gravx,double gravy, double gravz); +B3_SHARED_API int b3PhysicsParamSetTimeStep(b3SharedMemoryCommandHandle commandHandle, double timeStep); +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); -int b3PhysicsParamSetNumSubSteps(b3SharedMemoryCommandHandle commandHandle, int numSubSteps); -int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandHandle commandHandle, int enableRealTimeSimulation); -int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHandle, int numSolverIterations); -int b3PhysicsParamSetCollisionFilterMode(b3SharedMemoryCommandHandle commandHandle, int filterMode); +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); -int b3PhysicsParamSetUseSplitImpulse(b3SharedMemoryCommandHandle commandHandle, int useSplitImpulse); -int b3PhysicsParamSetSplitImpulsePenetrationThreshold(b3SharedMemoryCommandHandle commandHandle, double splitImpulsePenetrationThreshold); -int b3PhysicsParamSetContactBreakingThreshold(b3SharedMemoryCommandHandle commandHandle, double contactBreakingThreshold); -int b3PhysicsParamSetMaxNumCommandsPer1ms(b3SharedMemoryCommandHandle commandHandle, int maxNumCmdPer1ms); -int b3PhysicsParamSetEnableFileCaching(b3SharedMemoryCommandHandle commandHandle, int enableFileCaching); -int b3PhysicsParamSetRestitutionVelocityThreshold(b3SharedMemoryCommandHandle commandHandle, double restitutionVelocityThreshold); +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); +B3_SHARED_API int b3PhysicsParamSetMaxNumCommandsPer1ms(b3SharedMemoryCommandHandle commandHandle, int maxNumCmdPer1ms); +B3_SHARED_API int b3PhysicsParamSetEnableFileCaching(b3SharedMemoryCommandHandle commandHandle, int enableFileCaching); +B3_SHARED_API int b3PhysicsParamSetRestitutionVelocityThreshold(b3SharedMemoryCommandHandle commandHandle, double restitutionVelocityThreshold); //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 -int b3PhysicsParamSetInternalSimFlags(b3SharedMemoryCommandHandle commandHandle, int flags); +B3_SHARED_API int b3PhysicsParamSetInternalSimFlags(b3SharedMemoryCommandHandle commandHandle, int flags); -b3SharedMemoryCommandHandle b3InitStepSimulationCommand(b3PhysicsClientHandle physClient); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitStepSimulationCommand(b3PhysicsClientHandle physClient); -b3SharedMemoryCommandHandle b3InitResetSimulationCommand(b3PhysicsClientHandle physClient); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitResetSimulationCommand(b3PhysicsClientHandle physClient); ///Load a robot from a URDF file. Status type will CMD_URDF_LOADING_COMPLETED. ///Access the robot from the unique body index, through b3GetStatusBodyIndex(statusHandle); -b3SharedMemoryCommandHandle b3LoadUrdfCommandInit(b3PhysicsClientHandle physClient, const char* urdfFileName); +B3_SHARED_API b3SharedMemoryCommandHandle b3LoadUrdfCommandInit(b3PhysicsClientHandle physClient, const char* urdfFileName); -int b3LoadUrdfCommandSetStartPosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ); -int b3LoadUrdfCommandSetStartOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW); -int b3LoadUrdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody); -int b3LoadUrdfCommandSetUseFixedBase(b3SharedMemoryCommandHandle commandHandle, int useFixedBase); -int b3LoadUrdfCommandSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags); -int b3LoadUrdfCommandSetGlobalScaling(b3SharedMemoryCommandHandle commandHandle, double globalScaling); +B3_SHARED_API int b3LoadUrdfCommandSetStartPosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ); +B3_SHARED_API int b3LoadUrdfCommandSetStartOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW); +B3_SHARED_API int b3LoadUrdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody); +B3_SHARED_API int b3LoadUrdfCommandSetUseFixedBase(b3SharedMemoryCommandHandle commandHandle, int useFixedBase); +B3_SHARED_API int b3LoadUrdfCommandSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags); +B3_SHARED_API int b3LoadUrdfCommandSetGlobalScaling(b3SharedMemoryCommandHandle commandHandle, double globalScaling); -b3SharedMemoryCommandHandle b3LoadBulletCommandInit(b3PhysicsClientHandle physClient, const char* fileName); -b3SharedMemoryCommandHandle b3SaveBulletCommandInit(b3PhysicsClientHandle physClient, const char* fileName); -b3SharedMemoryCommandHandle b3LoadMJCFCommandInit(b3PhysicsClientHandle physClient, const char* fileName); -void b3LoadMJCFCommandSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags); +B3_SHARED_API b3SharedMemoryCommandHandle b3LoadBulletCommandInit(b3PhysicsClientHandle physClient, const char* fileName); +B3_SHARED_API b3SharedMemoryCommandHandle b3SaveBulletCommandInit(b3PhysicsClientHandle physClient, const char* fileName); +B3_SHARED_API b3SharedMemoryCommandHandle b3LoadMJCFCommandInit(b3PhysicsClientHandle physClient, const char* fileName); +B3_SHARED_API void b3LoadMJCFCommandSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags); ///compute the forces to achieve an acceleration, given a state q and qdot using inverse dynamics -b3SharedMemoryCommandHandle b3CalculateInverseDynamicsCommandInit(b3PhysicsClientHandle physClient, int bodyIndex, +B3_SHARED_API b3SharedMemoryCommandHandle b3CalculateInverseDynamicsCommandInit(b3PhysicsClientHandle physClient, int bodyIndex, const double* jointPositionsQ, const double* jointVelocitiesQdot, const double* jointAccelerations); -int b3GetStatusInverseDynamicsJointForces(b3SharedMemoryStatusHandle statusHandle, +B3_SHARED_API int b3GetStatusInverseDynamicsJointForces(b3SharedMemoryStatusHandle statusHandle, int* bodyUniqueId, int* dofCount, double* jointForces); -b3SharedMemoryCommandHandle b3CalculateJacobianCommandInit(b3PhysicsClientHandle physClient, int bodyIndex, int linkIndex, const double* localPosition, const double* jointPositionsQ, const double* jointVelocitiesQdot, const double* jointAccelerations); +B3_SHARED_API b3SharedMemoryCommandHandle b3CalculateJacobianCommandInit(b3PhysicsClientHandle physClient, int bodyIndex, int linkIndex, const double* localPosition, const double* jointPositionsQ, const double* jointVelocitiesQdot, const double* jointAccelerations); -int b3GetStatusJacobian(b3SharedMemoryStatusHandle statusHandle, double* linearJacobian, double* angularJacobian); +B3_SHARED_API int b3GetStatusJacobian(b3SharedMemoryStatusHandle statusHandle, double* linearJacobian, double* angularJacobian); ///compute the joint positions to move the end effector to a desired target using inverse kinematics -b3SharedMemoryCommandHandle b3CalculateInverseKinematicsCommandInit(b3PhysicsClientHandle physClient, int bodyIndex); -void b3CalculateInverseKinematicsAddTargetPurePosition(b3SharedMemoryCommandHandle commandHandle, int endEffectorLinkIndex, const double targetPosition[3]); -void b3CalculateInverseKinematicsAddTargetPositionWithOrientation(b3SharedMemoryCommandHandle commandHandle, int endEffectorLinkIndex, const double targetPosition[3], const double targetOrientation[4]); -void b3CalculateInverseKinematicsPosWithNullSpaceVel(b3SharedMemoryCommandHandle commandHandle, int numDof, int endEffectorLinkIndex, const double targetPosition[3], const double* lowerLimit, const double* upperLimit, const double* jointRange, const double* restPose); -void b3CalculateInverseKinematicsPosOrnWithNullSpaceVel(b3SharedMemoryCommandHandle commandHandle, int numDof, int endEffectorLinkIndex, const double targetPosition[3], const double targetOrientation[4], const double* lowerLimit, const double* upperLimit, const double* jointRange, const double* restPose); -void b3CalculateInverseKinematicsSetJointDamping(b3SharedMemoryCommandHandle commandHandle, int numDof, const double* jointDampingCoeff); -int b3GetStatusInverseKinematicsJointPositions(b3SharedMemoryStatusHandle statusHandle, +B3_SHARED_API b3SharedMemoryCommandHandle b3CalculateInverseKinematicsCommandInit(b3PhysicsClientHandle physClient, int bodyIndex); +B3_SHARED_API void b3CalculateInverseKinematicsAddTargetPurePosition(b3SharedMemoryCommandHandle commandHandle, int endEffectorLinkIndex, const double targetPosition[/*3*/]); +B3_SHARED_API void b3CalculateInverseKinematicsAddTargetPositionWithOrientation(b3SharedMemoryCommandHandle commandHandle, int endEffectorLinkIndex, const double targetPosition[/*3*/], const double targetOrientation[/*4*/]); +B3_SHARED_API void b3CalculateInverseKinematicsPosWithNullSpaceVel(b3SharedMemoryCommandHandle commandHandle, int numDof, int endEffectorLinkIndex, const double targetPosition[/*3*/], const double* lowerLimit, const double* upperLimit, const double* jointRange, const double* restPose); +B3_SHARED_API void b3CalculateInverseKinematicsPosOrnWithNullSpaceVel(b3SharedMemoryCommandHandle commandHandle, int numDof, int endEffectorLinkIndex, const double targetPosition[/*3*/], const double targetOrientation[/*4*/], const double* lowerLimit, const double* upperLimit, const double* jointRange, const double* restPose); +B3_SHARED_API void b3CalculateInverseKinematicsSetJointDamping(b3SharedMemoryCommandHandle commandHandle, int numDof, const double* jointDampingCoeff); +B3_SHARED_API int b3GetStatusInverseKinematicsJointPositions(b3SharedMemoryStatusHandle statusHandle, int* bodyUniqueId, int* dofCount, double* jointPositions); -b3SharedMemoryCommandHandle b3LoadSdfCommandInit(b3PhysicsClientHandle physClient, const char* sdfFileName); -int b3LoadSdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody); -int b3LoadSdfCommandSetUseGlobalScaling(b3SharedMemoryCommandHandle commandHandle, double globalScaling); +B3_SHARED_API b3SharedMemoryCommandHandle b3LoadSdfCommandInit(b3PhysicsClientHandle physClient, const char* sdfFileName); +B3_SHARED_API int b3LoadSdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody); +B3_SHARED_API int b3LoadSdfCommandSetUseGlobalScaling(b3SharedMemoryCommandHandle commandHandle, double globalScaling); -b3SharedMemoryCommandHandle b3SaveWorldCommandInit(b3PhysicsClientHandle physClient, const char* sdfFileName); +B3_SHARED_API b3SharedMemoryCommandHandle b3SaveWorldCommandInit(b3PhysicsClientHandle physClient, const char* sdfFileName); ///The b3JointControlCommandInit method is obsolete, use b3JointControlCommandInit2 instead -b3SharedMemoryCommandHandle b3JointControlCommandInit(b3PhysicsClientHandle physClient, int controlMode); +B3_SHARED_API b3SharedMemoryCommandHandle b3JointControlCommandInit(b3PhysicsClientHandle physClient, int controlMode); ///Set joint motor control variables such as desired position/angle, desired velocity, ///applied joint forces, dependent on the control mode (CONTROL_MODE_VELOCITY or CONTROL_MODE_TORQUE) -b3SharedMemoryCommandHandle b3JointControlCommandInit2(b3PhysicsClientHandle physClient, int bodyUniqueId, int controlMode); +B3_SHARED_API b3SharedMemoryCommandHandle b3JointControlCommandInit2(b3PhysicsClientHandle physClient, int bodyUniqueId, int controlMode); ///Only use when controlMode is CONTROL_MODE_POSITION_VELOCITY_PD -int b3JointControlSetDesiredPosition(b3SharedMemoryCommandHandle commandHandle, int qIndex, double value); -int b3JointControlSetKp(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value); -int b3JointControlSetKd(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value); +B3_SHARED_API int b3JointControlSetDesiredPosition(b3SharedMemoryCommandHandle commandHandle, int qIndex, double value); +B3_SHARED_API int b3JointControlSetKp(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value); +B3_SHARED_API int b3JointControlSetKd(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value); ///Only use when controlMode is CONTROL_MODE_VELOCITY -int b3JointControlSetDesiredVelocity(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value); /* find a better name for dof/q/u indices, point to b3JointInfo */ -int b3JointControlSetMaximumForce(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value); +B3_SHARED_API int b3JointControlSetDesiredVelocity(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value); /* find a better name for dof/q/u indices, point to b3JointInfo */ +B3_SHARED_API int b3JointControlSetMaximumForce(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value); ///Only use if when controlMode is CONTROL_MODE_TORQUE, -int b3JointControlSetDesiredForceTorque(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value); +B3_SHARED_API int b3JointControlSetDesiredForceTorque(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value); ///the creation of collision shapes and rigid bodies etc is likely going to change, ///but good to have a b3CreateBoxShapeCommandInit for now -b3SharedMemoryCommandHandle b3CreateCollisionShapeCommandInit(b3PhysicsClientHandle physClient); -int b3CreateCollisionShapeAddSphere(b3SharedMemoryCommandHandle commandHandle,double radius); -int b3CreateCollisionShapeAddBox(b3SharedMemoryCommandHandle commandHandle,double halfExtents[3]); -int b3CreateCollisionShapeAddCapsule(b3SharedMemoryCommandHandle commandHandle,double radius, double height); -int b3CreateCollisionShapeAddCylinder(b3SharedMemoryCommandHandle commandHandle,double radius, double height); -int b3CreateCollisionShapeAddPlane(b3SharedMemoryCommandHandle commandHandle, double planeNormal[3], double planeConstant); -int b3CreateCollisionShapeAddMesh(b3SharedMemoryCommandHandle commandHandle,const char* fileName, double meshScale[3]); -void b3CreateCollisionSetFlag(b3SharedMemoryCommandHandle commandHandle,int shapeIndex, int flags); +B3_SHARED_API b3SharedMemoryCommandHandle b3CreateCollisionShapeCommandInit(b3PhysicsClientHandle physClient); +B3_SHARED_API int b3CreateCollisionShapeAddSphere(b3SharedMemoryCommandHandle commandHandle,double radius); +B3_SHARED_API int b3CreateCollisionShapeAddBox(b3SharedMemoryCommandHandle commandHandle,double halfExtents[/*3*/]); +B3_SHARED_API int b3CreateCollisionShapeAddCapsule(b3SharedMemoryCommandHandle commandHandle,double radius, double height); +B3_SHARED_API int b3CreateCollisionShapeAddCylinder(b3SharedMemoryCommandHandle commandHandle,double radius, double height); +B3_SHARED_API int b3CreateCollisionShapeAddPlane(b3SharedMemoryCommandHandle commandHandle, double planeNormal[/*3*/], double planeConstant); +B3_SHARED_API int b3CreateCollisionShapeAddMesh(b3SharedMemoryCommandHandle commandHandle,const char* fileName, double meshScale[/*3*/]); +B3_SHARED_API void b3CreateCollisionSetFlag(b3SharedMemoryCommandHandle commandHandle,int shapeIndex, int flags); -void b3CreateCollisionShapeSetChildTransform(b3SharedMemoryCommandHandle commandHandle,int shapeIndex, double childPosition[3], double childOrientation[4]); +B3_SHARED_API void b3CreateCollisionShapeSetChildTransform(b3SharedMemoryCommandHandle commandHandle,int shapeIndex, double childPosition[/*3*/], double childOrientation[/*4*/]); -int b3GetStatusCollisionShapeUniqueId(b3SharedMemoryStatusHandle statusHandle); +B3_SHARED_API int b3GetStatusCollisionShapeUniqueId(b3SharedMemoryStatusHandle statusHandle); -b3SharedMemoryCommandHandle b3CreateVisualShapeCommandInit(b3PhysicsClientHandle physClient); -int b3GetStatusVisualShapeUniqueId(b3SharedMemoryStatusHandle statusHandle); +B3_SHARED_API b3SharedMemoryCommandHandle b3CreateVisualShapeCommandInit(b3PhysicsClientHandle physClient); +B3_SHARED_API int b3GetStatusVisualShapeUniqueId(b3SharedMemoryStatusHandle statusHandle); -b3SharedMemoryCommandHandle b3CreateMultiBodyCommandInit(b3PhysicsClientHandle physClient); -int b3CreateMultiBodyBase(b3SharedMemoryCommandHandle commandHandle, double mass, int collisionShapeUnique, int visualShapeUniqueId, double basePosition[3], double baseOrientation[4] , double baseInertialFramePosition[3], double baseInertialFrameOrientation[4]); +B3_SHARED_API b3SharedMemoryCommandHandle b3CreateMultiBodyCommandInit(b3PhysicsClientHandle physClient); +B3_SHARED_API int b3CreateMultiBodyBase(b3SharedMemoryCommandHandle commandHandle, double mass, int collisionShapeUnique, int visualShapeUniqueId, double basePosition[/*3*/], double baseOrientation[/*4*/] , double baseInertialFramePosition[/*3*/], double baseInertialFrameOrientation[/*4*/]); -int b3CreateMultiBodyLink(b3SharedMemoryCommandHandle commandHandle, double linkMass, double linkCollisionShapeIndex, +B3_SHARED_API int b3CreateMultiBodyLink(b3SharedMemoryCommandHandle commandHandle, double linkMass, double linkCollisionShapeIndex, double linkVisualShapeIndex, - double linkPosition[3], - double linkOrientation[4], - double linkInertialFramePosition[3], - double linkInertialFrameOrientation[4], + double linkPosition[/*3*/], + double linkOrientation[/*4*/], + double linkInertialFramePosition[/*3*/], + double linkInertialFrameOrientation[/*4*/], int linkParentIndex, int linkJointType, - double linkJointAxis[3]); + double linkJointAxis[/*3*/]); //useMaximalCoordinates are disabled by default, enabling them is experimental and not fully supported yet -void b3CreateMultiBodyUseMaximalCoordinates(b3SharedMemoryCommandHandle commandHandle); +B3_SHARED_API void b3CreateMultiBodyUseMaximalCoordinates(b3SharedMemoryCommandHandle commandHandle); //int b3CreateMultiBodyAddLink(b3SharedMemoryCommandHandle commandHandle, int jointType, int parentLinkIndex, double linkMass, int linkCollisionShapeUnique, int linkVisualShapeUniqueId); @@ -382,119 +390,119 @@ void b3CreateMultiBodyUseMaximalCoordinates(b3SharedMemoryCommandHandle commandH ///create a box of size (1,1,1) at world origin (0,0,0) at orientation quat (0,0,0,1) ///after that, you can optionally adjust the initial position, orientation and size -b3SharedMemoryCommandHandle b3CreateBoxShapeCommandInit(b3PhysicsClientHandle physClient); -int b3CreateBoxCommandSetStartPosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ); -int b3CreateBoxCommandSetStartOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW); -int b3CreateBoxCommandSetHalfExtents(b3SharedMemoryCommandHandle commandHandle, double halfExtentsX,double halfExtentsY,double halfExtentsZ); -int b3CreateBoxCommandSetMass(b3SharedMemoryCommandHandle commandHandle, double mass); -int b3CreateBoxCommandSetCollisionShapeType(b3SharedMemoryCommandHandle commandHandle, int collisionShapeType); -int b3CreateBoxCommandSetColorRGBA(b3SharedMemoryCommandHandle commandHandle, double red,double green,double blue, double alpha); +B3_SHARED_API b3SharedMemoryCommandHandle b3CreateBoxShapeCommandInit(b3PhysicsClientHandle physClient); +B3_SHARED_API int b3CreateBoxCommandSetStartPosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ); +B3_SHARED_API int b3CreateBoxCommandSetStartOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW); +B3_SHARED_API int b3CreateBoxCommandSetHalfExtents(b3SharedMemoryCommandHandle commandHandle, double halfExtentsX,double halfExtentsY,double halfExtentsZ); +B3_SHARED_API int b3CreateBoxCommandSetMass(b3SharedMemoryCommandHandle commandHandle, double mass); +B3_SHARED_API int b3CreateBoxCommandSetCollisionShapeType(b3SharedMemoryCommandHandle commandHandle, int collisionShapeType); +B3_SHARED_API int b3CreateBoxCommandSetColorRGBA(b3SharedMemoryCommandHandle commandHandle, double red,double green,double blue, double alpha); ///b3CreatePoseCommandInit will initialize (teleport) the pose of a body/robot. You can individually set the base position, ///base orientation and joint angles. This will set all velocities of base and joints to zero. ///This is not a robot control command using actuators/joint motors, but manual repositioning the robot. -b3SharedMemoryCommandHandle b3CreatePoseCommandInit(b3PhysicsClientHandle physClient, int bodyIndex); -int b3CreatePoseCommandSetBasePosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ); -int b3CreatePoseCommandSetBaseOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW); -int b3CreatePoseCommandSetBaseLinearVelocity(b3SharedMemoryCommandHandle commandHandle, double linVel[3]); -int b3CreatePoseCommandSetBaseAngularVelocity(b3SharedMemoryCommandHandle commandHandle, double angVel[3]); +B3_SHARED_API b3SharedMemoryCommandHandle b3CreatePoseCommandInit(b3PhysicsClientHandle physClient, int bodyIndex); +B3_SHARED_API int b3CreatePoseCommandSetBasePosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ); +B3_SHARED_API int b3CreatePoseCommandSetBaseOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW); +B3_SHARED_API int b3CreatePoseCommandSetBaseLinearVelocity(b3SharedMemoryCommandHandle commandHandle, double linVel[/*3*/]); +B3_SHARED_API int b3CreatePoseCommandSetBaseAngularVelocity(b3SharedMemoryCommandHandle commandHandle, double angVel[/*3*/]); -int b3CreatePoseCommandSetJointPositions(b3SharedMemoryCommandHandle commandHandle, int numJointPositions, const double* jointPositions); -int b3CreatePoseCommandSetJointPosition(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, int jointIndex, double jointPosition); +B3_SHARED_API int b3CreatePoseCommandSetJointPositions(b3SharedMemoryCommandHandle commandHandle, int numJointPositions, const double* jointPositions); +B3_SHARED_API int b3CreatePoseCommandSetJointPosition(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, int jointIndex, double jointPosition); -int b3CreatePoseCommandSetJointVelocities(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, int numJointVelocities, const double* jointVelocities); -int b3CreatePoseCommandSetJointVelocity(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, int jointIndex, double jointVelocity); +B3_SHARED_API int b3CreatePoseCommandSetJointVelocities(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, int numJointVelocities, const double* jointVelocities); +B3_SHARED_API int b3CreatePoseCommandSetJointVelocity(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, int jointIndex, double jointVelocity); ///We are currently not reading the sensor information from the URDF file, and programmatically assign sensors. ///This is rather inconsistent, to mix programmatical creation with loading from file. -b3SharedMemoryCommandHandle b3CreateSensorCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId); -int b3CreateSensorEnable6DofJointForceTorqueSensor(b3SharedMemoryCommandHandle commandHandle, int jointIndex, int enable); +B3_SHARED_API b3SharedMemoryCommandHandle b3CreateSensorCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId); +B3_SHARED_API int b3CreateSensorEnable6DofJointForceTorqueSensor(b3SharedMemoryCommandHandle commandHandle, int jointIndex, int enable); ///b3CreateSensorEnableIMUForLink is not implemented yet. ///For now, if the IMU is located in the root link, use the root world transform to mimic an IMU. -int b3CreateSensorEnableIMUForLink(b3SharedMemoryCommandHandle commandHandle, int linkIndex, int enable); +B3_SHARED_API int b3CreateSensorEnableIMUForLink(b3SharedMemoryCommandHandle commandHandle, int linkIndex, int enable); -b3SharedMemoryCommandHandle b3RequestActualStateCommandInit(b3PhysicsClientHandle physClient,int bodyUniqueId); -int b3RequestActualStateCommandComputeLinkVelocity(b3SharedMemoryCommandHandle commandHandle, int computeLinkVelocity); +B3_SHARED_API b3SharedMemoryCommandHandle b3RequestActualStateCommandInit(b3PhysicsClientHandle physClient,int bodyUniqueId); +B3_SHARED_API int b3RequestActualStateCommandComputeLinkVelocity(b3SharedMemoryCommandHandle commandHandle, int computeLinkVelocity); -int b3GetJointState(b3PhysicsClientHandle physClient, b3SharedMemoryStatusHandle statusHandle, int jointIndex, struct b3JointSensorState *state); -int b3GetLinkState(b3PhysicsClientHandle physClient, b3SharedMemoryStatusHandle statusHandle, int linkIndex, struct b3LinkState *state); +B3_SHARED_API int b3GetJointState(b3PhysicsClientHandle physClient, b3SharedMemoryStatusHandle statusHandle, int jointIndex, struct b3JointSensorState *state); +B3_SHARED_API int b3GetLinkState(b3PhysicsClientHandle physClient, b3SharedMemoryStatusHandle statusHandle, int linkIndex, struct b3LinkState *state); -b3SharedMemoryCommandHandle b3PickBody(b3PhysicsClientHandle physClient, double rayFromWorldX, +B3_SHARED_API b3SharedMemoryCommandHandle b3PickBody(b3PhysicsClientHandle physClient, double rayFromWorldX, double rayFromWorldY, double rayFromWorldZ, double rayToWorldX, double rayToWorldY, double rayToWorldZ); -b3SharedMemoryCommandHandle b3MovePickedBody(b3PhysicsClientHandle physClient, double rayFromWorldX, +B3_SHARED_API b3SharedMemoryCommandHandle b3MovePickedBody(b3PhysicsClientHandle physClient, double rayFromWorldX, double rayFromWorldY, double rayFromWorldZ, double rayToWorldX, double rayToWorldY, double rayToWorldZ); -b3SharedMemoryCommandHandle b3RemovePickingConstraint(b3PhysicsClientHandle physClient); +B3_SHARED_API b3SharedMemoryCommandHandle b3RemovePickingConstraint(b3PhysicsClientHandle physClient); -b3SharedMemoryCommandHandle b3CreateRaycastCommandInit(b3PhysicsClientHandle physClient, double rayFromWorldX, +B3_SHARED_API b3SharedMemoryCommandHandle b3CreateRaycastCommandInit(b3PhysicsClientHandle physClient, double rayFromWorldX, double rayFromWorldY, double rayFromWorldZ, double rayToWorldX, double rayToWorldY, double rayToWorldZ); -b3SharedMemoryCommandHandle b3CreateRaycastBatchCommandInit(b3PhysicsClientHandle physClient); -void b3RaycastBatchAddRay(b3SharedMemoryCommandHandle commandHandle, const double rayFromWorld[3], const double rayToWorld[3]); +B3_SHARED_API b3SharedMemoryCommandHandle b3CreateRaycastBatchCommandInit(b3PhysicsClientHandle physClient); +B3_SHARED_API void b3RaycastBatchAddRay(b3SharedMemoryCommandHandle commandHandle, const double rayFromWorld[/*3*/], const double rayToWorld[/*3*/]); -void b3GetRaycastInformation(b3PhysicsClientHandle physClient, struct b3RaycastInformation* raycastInfo); +B3_SHARED_API void b3GetRaycastInformation(b3PhysicsClientHandle physClient, struct b3RaycastInformation* raycastInfo); /// Apply external force at the body (or link) center of mass, in world space/Cartesian coordinates. -b3SharedMemoryCommandHandle b3ApplyExternalForceCommandInit(b3PhysicsClientHandle physClient); -void b3ApplyExternalForce(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkId, const double force[3], const double position[3], int flags); -void b3ApplyExternalTorque(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkId, const double torque[3], int flags); +B3_SHARED_API b3SharedMemoryCommandHandle b3ApplyExternalForceCommandInit(b3PhysicsClientHandle physClient); +B3_SHARED_API void b3ApplyExternalForce(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkId, const double force[/*3*/], const double position[/*3*/], int flags); +B3_SHARED_API void b3ApplyExternalTorque(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkId, const double torque[/*3*/], int flags); ///experiments of robots interacting with non-rigid objects (such as btSoftBody) -b3SharedMemoryCommandHandle b3LoadBunnyCommandInit(b3PhysicsClientHandle physClient); -int b3LoadBunnySetScale(b3SharedMemoryCommandHandle commandHandle, double scale); -int b3LoadBunnySetMass(b3SharedMemoryCommandHandle commandHandle, double mass); -int b3LoadBunnySetCollisionMargin(b3SharedMemoryCommandHandle commandHandle, double collisionMargin); +B3_SHARED_API b3SharedMemoryCommandHandle b3LoadBunnyCommandInit(b3PhysicsClientHandle physClient); +B3_SHARED_API int b3LoadBunnySetScale(b3SharedMemoryCommandHandle commandHandle, double scale); +B3_SHARED_API int b3LoadBunnySetMass(b3SharedMemoryCommandHandle commandHandle, double mass); +B3_SHARED_API int b3LoadBunnySetCollisionMargin(b3SharedMemoryCommandHandle commandHandle, double collisionMargin); -b3SharedMemoryCommandHandle b3RequestVREventsCommandInit(b3PhysicsClientHandle physClient); -void b3VREventsSetDeviceTypeFilter(b3SharedMemoryCommandHandle commandHandle, int deviceTypeFilter); +B3_SHARED_API b3SharedMemoryCommandHandle b3RequestVREventsCommandInit(b3PhysicsClientHandle physClient); +B3_SHARED_API void b3VREventsSetDeviceTypeFilter(b3SharedMemoryCommandHandle commandHandle, int deviceTypeFilter); -void b3GetVREventsData(b3PhysicsClientHandle physClient, struct b3VREventsData* vrEventsData); +B3_SHARED_API void b3GetVREventsData(b3PhysicsClientHandle physClient, struct b3VREventsData* vrEventsData); -b3SharedMemoryCommandHandle b3SetVRCameraStateCommandInit(b3PhysicsClientHandle physClient); -int b3SetVRCameraRootPosition(b3SharedMemoryCommandHandle commandHandle, double rootPos[3]); -int b3SetVRCameraRootOrientation(b3SharedMemoryCommandHandle commandHandle, double rootOrn[4]); -int b3SetVRCameraTrackingObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId); -int b3SetVRCameraTrackingObjectFlag(b3SharedMemoryCommandHandle commandHandle, int flag); +B3_SHARED_API b3SharedMemoryCommandHandle b3SetVRCameraStateCommandInit(b3PhysicsClientHandle physClient); +B3_SHARED_API int b3SetVRCameraRootPosition(b3SharedMemoryCommandHandle commandHandle, double rootPos[/*3*/]); +B3_SHARED_API int b3SetVRCameraRootOrientation(b3SharedMemoryCommandHandle commandHandle, double rootOrn[/*4*/]); +B3_SHARED_API int b3SetVRCameraTrackingObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId); +B3_SHARED_API int b3SetVRCameraTrackingObjectFlag(b3SharedMemoryCommandHandle commandHandle, int flag); -b3SharedMemoryCommandHandle b3RequestKeyboardEventsCommandInit(b3PhysicsClientHandle physClient); -void b3GetKeyboardEventsData(b3PhysicsClientHandle physClient, struct b3KeyboardEventsData* keyboardEventsData); +B3_SHARED_API b3SharedMemoryCommandHandle b3RequestKeyboardEventsCommandInit(b3PhysicsClientHandle physClient); +B3_SHARED_API void b3GetKeyboardEventsData(b3PhysicsClientHandle physClient, struct b3KeyboardEventsData* keyboardEventsData); -b3SharedMemoryCommandHandle b3RequestMouseEventsCommandInit(b3PhysicsClientHandle physClient); -void b3GetMouseEventsData(b3PhysicsClientHandle physClient, struct b3MouseEventsData* mouseEventsData); +B3_SHARED_API b3SharedMemoryCommandHandle b3RequestMouseEventsCommandInit(b3PhysicsClientHandle physClient); +B3_SHARED_API void b3GetMouseEventsData(b3PhysicsClientHandle physClient, struct b3MouseEventsData* mouseEventsData); -b3SharedMemoryCommandHandle b3StateLoggingCommandInit(b3PhysicsClientHandle physClient); -int b3StateLoggingStart(b3SharedMemoryCommandHandle commandHandle, int loggingType, const char* fileName); -int b3StateLoggingAddLoggingObjectUniqueId(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId); -int b3StateLoggingSetMaxLogDof(b3SharedMemoryCommandHandle commandHandle, int maxLogDof); -int b3StateLoggingSetLinkIndexA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA); -int b3StateLoggingSetLinkIndexB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB); -int b3StateLoggingSetBodyAUniqueId(b3SharedMemoryCommandHandle commandHandle, int bodyAUniqueId); -int b3StateLoggingSetBodyBUniqueId(b3SharedMemoryCommandHandle commandHandle, int bodyBUniqueId); -int b3StateLoggingSetDeviceTypeFilter(b3SharedMemoryCommandHandle commandHandle, int deviceTypeFilter); -int b3StateLoggingSetLogFlags(b3SharedMemoryCommandHandle commandHandle, int logFlags); +B3_SHARED_API b3SharedMemoryCommandHandle b3StateLoggingCommandInit(b3PhysicsClientHandle physClient); +B3_SHARED_API int b3StateLoggingStart(b3SharedMemoryCommandHandle commandHandle, int loggingType, const char* fileName); +B3_SHARED_API int b3StateLoggingAddLoggingObjectUniqueId(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId); +B3_SHARED_API int b3StateLoggingSetMaxLogDof(b3SharedMemoryCommandHandle commandHandle, int maxLogDof); +B3_SHARED_API int b3StateLoggingSetLinkIndexA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA); +B3_SHARED_API int b3StateLoggingSetLinkIndexB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB); +B3_SHARED_API int b3StateLoggingSetBodyAUniqueId(b3SharedMemoryCommandHandle commandHandle, int bodyAUniqueId); +B3_SHARED_API int b3StateLoggingSetBodyBUniqueId(b3SharedMemoryCommandHandle commandHandle, int bodyBUniqueId); +B3_SHARED_API int b3StateLoggingSetDeviceTypeFilter(b3SharedMemoryCommandHandle commandHandle, int deviceTypeFilter); +B3_SHARED_API int b3StateLoggingSetLogFlags(b3SharedMemoryCommandHandle commandHandle, int logFlags); -int b3GetStatusLoggingUniqueId(b3SharedMemoryStatusHandle statusHandle); -int b3StateLoggingStop(b3SharedMemoryCommandHandle commandHandle, int loggingUniqueId); +B3_SHARED_API int b3GetStatusLoggingUniqueId(b3SharedMemoryStatusHandle statusHandle); +B3_SHARED_API int b3StateLoggingStop(b3SharedMemoryCommandHandle commandHandle, int loggingUniqueId); -b3SharedMemoryCommandHandle b3ProfileTimingCommandInit(b3PhysicsClientHandle physClient, const char* name); -void b3SetProfileTimingDuractionInMicroSeconds(b3SharedMemoryCommandHandle commandHandle, int duration); +B3_SHARED_API b3SharedMemoryCommandHandle b3ProfileTimingCommandInit(b3PhysicsClientHandle physClient, const char* name); +B3_SHARED_API void b3SetProfileTimingDuractionInMicroSeconds(b3SharedMemoryCommandHandle commandHandle, int duration); -void b3SetTimeOut(b3PhysicsClientHandle physClient, double timeOutInSeconds); -double b3GetTimeOut(b3PhysicsClientHandle physClient); +B3_SHARED_API void b3SetTimeOut(b3PhysicsClientHandle physClient, double timeOutInSeconds); +B3_SHARED_API double b3GetTimeOut(b3PhysicsClientHandle physClient); -b3SharedMemoryCommandHandle b3SetAdditionalSearchPath(b3PhysicsClientHandle physClient, char* path); +B3_SHARED_API b3SharedMemoryCommandHandle b3SetAdditionalSearchPath(b3PhysicsClientHandle physClient, char* path); -void b3MultiplyTransforms(const double posA[3], const double ornA[4], const double posB[3], const double ornB[4], double outPos[3], double outOrn[4]); -void b3InvertTransform(const double pos[3], const double orn[4], double outPos[3], double outOrn[4]); +B3_SHARED_API void b3MultiplyTransforms(const double posA[/*3*/], const double ornA[/*4*/], const double posB[/*3*/], const double ornB[/*4*/], double outPos[/*3*/], double outOrn[/*4*/]); +B3_SHARED_API void b3InvertTransform(const double pos[/*3*/], const double orn[/*4*/], double outPos[/*3*/], double outOrn[/*4*/]); #ifdef __cplusplus } diff --git a/examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp b/examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp index 36c794f80..eedcb0160 100644 --- a/examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp +++ b/examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp @@ -2,7 +2,7 @@ #include "PhysicsClientSharedMemory.h" -b3PhysicsClientHandle b3ConnectSharedMemory(int key) +B3_SHARED_API b3PhysicsClientHandle b3ConnectSharedMemory(int key) { PhysicsClientSharedMemory* cl = new PhysicsClientSharedMemory(); cl->setSharedMemoryKey(key); diff --git a/examples/SharedMemory/PhysicsClientSharedMemory_C_API.h b/examples/SharedMemory/PhysicsClientSharedMemory_C_API.h index 2a4e4e665..44f9997d7 100644 --- a/examples/SharedMemory/PhysicsClientSharedMemory_C_API.h +++ b/examples/SharedMemory/PhysicsClientSharedMemory_C_API.h @@ -7,7 +7,7 @@ extern "C" { #endif - b3PhysicsClientHandle b3ConnectSharedMemory(int key); +B3_SHARED_API b3PhysicsClientHandle b3ConnectSharedMemory(int key); #ifdef __cplusplus } diff --git a/examples/SharedMemory/PhysicsClientTCP_C_API.cpp b/examples/SharedMemory/PhysicsClientTCP_C_API.cpp index e333b967a..6efd39f1e 100644 --- a/examples/SharedMemory/PhysicsClientTCP_C_API.cpp +++ b/examples/SharedMemory/PhysicsClientTCP_C_API.cpp @@ -4,7 +4,7 @@ #include "PhysicsDirect.h" #include -b3PhysicsClientHandle b3ConnectPhysicsTCP(const char* hostName, int port) +B3_SHARED_API b3PhysicsClientHandle b3ConnectPhysicsTCP(const char* hostName, int port) { TcpNetworkedPhysicsProcessor* tcp = new TcpNetworkedPhysicsProcessor(hostName, port); diff --git a/examples/SharedMemory/PhysicsClientTCP_C_API.h b/examples/SharedMemory/PhysicsClientTCP_C_API.h index dee180377..53216eeec 100644 --- a/examples/SharedMemory/PhysicsClientTCP_C_API.h +++ b/examples/SharedMemory/PhysicsClientTCP_C_API.h @@ -9,7 +9,7 @@ extern "C" { ///send physics commands using TCP networking - b3PhysicsClientHandle b3ConnectPhysicsTCP(const char* hostName, int port); +B3_SHARED_API b3PhysicsClientHandle b3ConnectPhysicsTCP(const char* hostName, int port); #ifdef __cplusplus diff --git a/examples/SharedMemory/PhysicsClientUDP_C_API.cpp b/examples/SharedMemory/PhysicsClientUDP_C_API.cpp index c3b024c43..50b8b39eb 100644 --- a/examples/SharedMemory/PhysicsClientUDP_C_API.cpp +++ b/examples/SharedMemory/PhysicsClientUDP_C_API.cpp @@ -5,7 +5,7 @@ #include //think more about naming. The b3ConnectPhysicsLoopback -b3PhysicsClientHandle b3ConnectPhysicsUDP(const char* hostName, int port) +B3_SHARED_API b3PhysicsClientHandle b3ConnectPhysicsUDP(const char* hostName, int port) { UdpNetworkedPhysicsProcessor* udp = new UdpNetworkedPhysicsProcessor(hostName, port); diff --git a/examples/SharedMemory/PhysicsClientUDP_C_API.h b/examples/SharedMemory/PhysicsClientUDP_C_API.h index fdb97bcab..8ea5ef027 100644 --- a/examples/SharedMemory/PhysicsClientUDP_C_API.h +++ b/examples/SharedMemory/PhysicsClientUDP_C_API.h @@ -9,7 +9,7 @@ extern "C" { ///send physics commands using UDP networking - b3PhysicsClientHandle b3ConnectPhysicsUDP(const char* hostName, int port); +B3_SHARED_API b3PhysicsClientHandle b3ConnectPhysicsUDP(const char* hostName, int port); #ifdef __cplusplus diff --git a/examples/SharedMemory/PhysicsDirectC_API.cpp b/examples/SharedMemory/PhysicsDirectC_API.cpp index 50a89b34f..803d36728 100644 --- a/examples/SharedMemory/PhysicsDirectC_API.cpp +++ b/examples/SharedMemory/PhysicsDirectC_API.cpp @@ -7,7 +7,7 @@ //think more about naming. The b3ConnectPhysicsLoopback -b3PhysicsClientHandle b3ConnectPhysicsDirect() +B3_SHARED_API b3PhysicsClientHandle b3ConnectPhysicsDirect() { PhysicsServerCommandProcessor* sdk = new PhysicsServerCommandProcessor; diff --git a/examples/SharedMemory/PhysicsDirectC_API.h b/examples/SharedMemory/PhysicsDirectC_API.h index 17681af61..7060bb832 100644 --- a/examples/SharedMemory/PhysicsDirectC_API.h +++ b/examples/SharedMemory/PhysicsDirectC_API.h @@ -9,7 +9,7 @@ extern "C" { ///think more about naming. Directly execute commands without transport (no shared memory, UDP, socket, grpc etc) -b3PhysicsClientHandle b3ConnectPhysicsDirect(); +B3_SHARED_API b3PhysicsClientHandle b3ConnectPhysicsDirect(); #ifdef __cplusplus diff --git a/examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp b/examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp index b82d550a6..3c13898ba 100644 --- a/examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp +++ b/examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp @@ -83,7 +83,7 @@ public: }; -b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectMainThread(int argc, char* argv[]) +B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectMainThread(int argc, char* argv[]) { InProcessPhysicsClientSharedMemoryMainThread* cl = new InProcessPhysicsClientSharedMemoryMainThread(argc, argv, 1); cl->setSharedMemoryKey(SHARED_MEMORY_KEY+1); @@ -91,7 +91,7 @@ b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectMainThread(int arg return (b3PhysicsClientHandle ) cl; } -b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectMainThreadSharedMemory(int argc, char* argv[]) +B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectMainThreadSharedMemory(int argc, char* argv[]) { InProcessPhysicsClientSharedMemoryMainThread* cl = new InProcessPhysicsClientSharedMemoryMainThread(argc, argv, 0); cl->setSharedMemoryKey(SHARED_MEMORY_KEY+1); @@ -133,7 +133,7 @@ public: }; -b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnect(int argc, char* argv[]) +B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnect(int argc, char* argv[]) { InProcessPhysicsClientSharedMemory* cl = new InProcessPhysicsClientSharedMemory(argc, argv, 1); @@ -141,7 +141,7 @@ b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnect(int argc, char* a cl->connect(); return (b3PhysicsClientHandle ) cl; } -b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectSharedMemory(int argc, char* argv[]) +B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectSharedMemory(int argc, char* argv[]) { InProcessPhysicsClientSharedMemory* cl = new InProcessPhysicsClientSharedMemory(argc, argv, 0); @@ -248,7 +248,7 @@ int b3InProcessMouseButtonCallback(b3PhysicsClientHandle clientHandle, int butto } -b3PhysicsClientHandle b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect(void* guiHelperPtr) +B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect(void* guiHelperPtr) { GUIHelperInterface* guiHelper = (GUIHelperInterface*) guiHelperPtr; InProcessPhysicsClientExistingExampleBrowser* cl = new InProcessPhysicsClientExistingExampleBrowser(guiHelper); diff --git a/examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.h b/examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.h index 04acba313..9f2a82be0 100644 --- a/examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.h +++ b/examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.h @@ -10,13 +10,13 @@ extern "C" { ///think more about naming. The b3ConnectPhysicsLoopback -b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnect(int argc, char* argv[]); -b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectSharedMemory(int argc, char* argv[]); +B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnect(int argc, char* argv[]); +B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectSharedMemory(int argc, char* argv[]); -b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectMainThread(int argc, char* argv[]); -b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectMainThreadSharedMemory(int argc, char* argv[]); +B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectMainThread(int argc, char* argv[]); +B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectMainThreadSharedMemory(int argc, char* argv[]); -b3PhysicsClientHandle b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect(void* guiHelperPtr); +B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect(void* guiHelperPtr); ///ignore the following APIs, they are for internal use for example browser void b3InProcessRenderSceneInternal(b3PhysicsClientHandle clientHandle); diff --git a/examples/StandaloneMain/hellovr_opengl_main.cpp b/examples/StandaloneMain/hellovr_opengl_main.cpp index ad81cad3c..1e48f879f 100644 --- a/examples/StandaloneMain/hellovr_opengl_main.cpp +++ b/examples/StandaloneMain/hellovr_opengl_main.cpp @@ -1808,6 +1808,8 @@ void CMainApplication::RenderStereoTargets() m_app->m_instancingRenderer->getActiveCamera()->setCameraUpVector(mat[0],mat[1],mat[2]); m_app->m_instancingRenderer->getActiveCamera()->setVRCamera(viewMatLeft.get(),m_mat4ProjectionLeft.get()); m_app->m_instancingRenderer->updateCamera(m_app->getUpAxis()); + m_app->m_instancingRenderer->getActiveCamera()->setVRCamera(viewMatLeft.get(),m_mat4ProjectionLeft.get()); + } glBindFramebuffer( GL_FRAMEBUFFER, leftEyeDesc.m_nRenderFramebufferId ); @@ -1866,6 +1868,7 @@ void CMainApplication::RenderStereoTargets() Matrix4 viewMatRight = m_mat4eyePosRight * m_mat4HMDPose * rotYtoZ; m_app->m_instancingRenderer->getActiveCamera()->setVRCamera(viewMatRight.get(),m_mat4ProjectionRight.get()); m_app->m_instancingRenderer->updateCamera(m_app->getUpAxis()); + m_app->m_instancingRenderer->getActiveCamera()->setVRCamera(viewMatRight.get(),m_mat4ProjectionRight.get()); } glBindFramebuffer( GL_FRAMEBUFFER, rightEyeDesc.m_nRenderFramebufferId ); diff --git a/examples/pybullet/unity3d/autogen/NativeMethods.cs b/examples/pybullet/unity3d/autogen/NativeMethods.cs new file mode 100644 index 000000000..b0d3521e6 --- /dev/null +++ b/examples/pybullet/unity3d/autogen/NativeMethods.cs @@ -0,0 +1,3113 @@ + +public partial class NativeConstants { + + /// PHYSICS_CLIENT_C_API_H -> + /// Error generating expression: Value cannot be null. + ///Parameter name: node + public const string PHYSICS_CLIENT_C_API_H = ""; + + /// SHARED_MEMORY_PUBLIC_H -> + /// Error generating expression: Value cannot be null. + ///Parameter name: node + public const string SHARED_MEMORY_PUBLIC_H = ""; + + /// SHARED_MEMORY_KEY -> 12347 + public const int SHARED_MEMORY_KEY = 12347; + + /// SHARED_MEMORY_MAGIC_NUMBER -> 201708270 + public const int SHARED_MEMORY_MAGIC_NUMBER = 201708270; + + /// MAX_VR_BUTTONS -> 64 + public const int MAX_VR_BUTTONS = 64; + + /// MAX_VR_CONTROLLERS -> 8 + public const int MAX_VR_CONTROLLERS = 8; + + /// MAX_RAY_INTERSECTION_BATCH_SIZE -> 256 + public const int MAX_RAY_INTERSECTION_BATCH_SIZE = 256; + + /// MAX_RAY_HITS -> MAX_RAY_INTERSECTION_BATCH_SIZE + public const int MAX_RAY_HITS = NativeConstants.MAX_RAY_INTERSECTION_BATCH_SIZE; + + /// MAX_KEYBOARD_EVENTS -> 256 + public const int MAX_KEYBOARD_EVENTS = 256; + + /// MAX_MOUSE_EVENTS -> 256 + public const int MAX_MOUSE_EVENTS = 256; + + /// VISUAL_SHAPE_MAX_PATH_LEN -> 1024 + public const int VISUAL_SHAPE_MAX_PATH_LEN = 1024; + + /// Warning: Generation of Method Macros is not supported at this time + /// B3_DECLARE_HANDLE -> "(name) typedef struct name##__ { int unused; } *name" + public const string B3_DECLARE_HANDLE = "(name) typedef struct name##__ { int unused; } *name"; + + /// PHYSICS_CLIENT_SHARED_MEMORY_H -> + /// Error generating expression: Value cannot be null. + ///Parameter name: node + public const string PHYSICS_CLIENT_SHARED_MEMORY_H = ""; + + /// PHYSICS_CLIENT_SHARED_MEMORY2_H -> + /// Error generating expression: Value cannot be null. + ///Parameter name: node + public const string PHYSICS_CLIENT_SHARED_MEMORY2_H = ""; + + /// PHYSICS_DIRECT_C_API_H -> + /// Error generating expression: Value cannot be null. + ///Parameter name: node + public const string PHYSICS_DIRECT_C_API_H = ""; + + /// IN_PROCESS_PHYSICS_C_API_H -> + /// Error generating expression: Value cannot be null. + ///Parameter name: node + public const string IN_PROCESS_PHYSICS_C_API_H = ""; +} + +public enum EnumSharedMemoryClientCommand { + + CMD_LOAD_SDF, + + CMD_LOAD_URDF, + + CMD_LOAD_BULLET, + + CMD_SAVE_BULLET, + + CMD_LOAD_MJCF, + + CMD_LOAD_BUNNY, + + CMD_SEND_BULLET_DATA_STREAM, + + CMD_CREATE_BOX_COLLISION_SHAPE, + + CMD_CREATE_RIGID_BODY, + + CMD_DELETE_RIGID_BODY, + + CMD_CREATE_SENSOR, + + CMD_INIT_POSE, + + CMD_SEND_PHYSICS_SIMULATION_PARAMETERS, + + CMD_SEND_DESIRED_STATE, + + CMD_REQUEST_ACTUAL_STATE, + + CMD_REQUEST_DEBUG_LINES, + + CMD_REQUEST_BODY_INFO, + + CMD_REQUEST_INTERNAL_DATA, + + CMD_STEP_FORWARD_SIMULATION, + + CMD_RESET_SIMULATION, + + CMD_PICK_BODY, + + CMD_MOVE_PICKED_BODY, + + CMD_REMOVE_PICKING_CONSTRAINT_BODY, + + CMD_REQUEST_CAMERA_IMAGE_DATA, + + CMD_APPLY_EXTERNAL_FORCE, + + CMD_CALCULATE_INVERSE_DYNAMICS, + + CMD_CALCULATE_INVERSE_KINEMATICS, + + CMD_CALCULATE_JACOBIAN, + + CMD_USER_CONSTRAINT, + + CMD_REQUEST_CONTACT_POINT_INFORMATION, + + CMD_REQUEST_RAY_CAST_INTERSECTIONS, + + CMD_REQUEST_AABB_OVERLAP, + + CMD_SAVE_WORLD, + + CMD_REQUEST_VISUAL_SHAPE_INFO, + + CMD_UPDATE_VISUAL_SHAPE, + + CMD_LOAD_TEXTURE, + + CMD_SET_SHADOW, + + CMD_USER_DEBUG_DRAW, + + CMD_REQUEST_VR_EVENTS_DATA, + + CMD_SET_VR_CAMERA_STATE, + + CMD_SYNC_BODY_INFO, + + CMD_STATE_LOGGING, + + CMD_CONFIGURE_OPENGL_VISUALIZER, + + CMD_REQUEST_KEYBOARD_EVENTS_DATA, + + CMD_REQUEST_OPENGL_VISUALIZER_CAMERA, + + CMD_REMOVE_BODY, + + CMD_CHANGE_DYNAMICS_INFO, + + CMD_GET_DYNAMICS_INFO, + + CMD_PROFILE_TIMING, + + CMD_CREATE_COLLISION_SHAPE, + + CMD_CREATE_VISUAL_SHAPE, + + CMD_CREATE_MULTI_BODY, + + CMD_REQUEST_COLLISION_INFO, + + CMD_REQUEST_MOUSE_EVENTS_DATA, + + CMD_CHANGE_TEXTURE, + + CMD_SET_ADDITIONAL_SEARCH_PATH, + + CMD_MAX_CLIENT_COMMANDS, +} + +public enum EnumSharedMemoryServerStatus { + + /// CMD_SHARED_MEMORY_NOT_INITIALIZED -> 0 + CMD_SHARED_MEMORY_NOT_INITIALIZED = 0, + + CMD_WAITING_FOR_CLIENT_COMMAND, + + CMD_CLIENT_COMMAND_COMPLETED, + + CMD_UNKNOWN_COMMAND_FLUSHED, + + CMD_SDF_LOADING_COMPLETED, + + CMD_SDF_LOADING_FAILED, + + CMD_URDF_LOADING_COMPLETED, + + CMD_URDF_LOADING_FAILED, + + CMD_BULLET_LOADING_COMPLETED, + + CMD_BULLET_LOADING_FAILED, + + CMD_BULLET_SAVING_COMPLETED, + + CMD_BULLET_SAVING_FAILED, + + CMD_MJCF_LOADING_COMPLETED, + + CMD_MJCF_LOADING_FAILED, + + CMD_REQUEST_INTERNAL_DATA_COMPLETED, + + CMD_REQUEST_INTERNAL_DATA_FAILED, + + CMD_BULLET_DATA_STREAM_RECEIVED_COMPLETED, + + CMD_BULLET_DATA_STREAM_RECEIVED_FAILED, + + CMD_BOX_COLLISION_SHAPE_CREATION_COMPLETED, + + CMD_RIGID_BODY_CREATION_COMPLETED, + + CMD_SET_JOINT_FEEDBACK_COMPLETED, + + CMD_ACTUAL_STATE_UPDATE_COMPLETED, + + CMD_ACTUAL_STATE_UPDATE_FAILED, + + CMD_DEBUG_LINES_COMPLETED, + + CMD_DEBUG_LINES_OVERFLOW_FAILED, + + CMD_DESIRED_STATE_RECEIVED_COMPLETED, + + CMD_STEP_FORWARD_SIMULATION_COMPLETED, + + CMD_RESET_SIMULATION_COMPLETED, + + CMD_CAMERA_IMAGE_COMPLETED, + + CMD_CAMERA_IMAGE_FAILED, + + CMD_BODY_INFO_COMPLETED, + + CMD_BODY_INFO_FAILED, + + CMD_INVALID_STATUS, + + CMD_CALCULATED_INVERSE_DYNAMICS_COMPLETED, + + CMD_CALCULATED_INVERSE_DYNAMICS_FAILED, + + CMD_CALCULATED_JACOBIAN_COMPLETED, + + CMD_CALCULATED_JACOBIAN_FAILED, + + CMD_CONTACT_POINT_INFORMATION_COMPLETED, + + CMD_CONTACT_POINT_INFORMATION_FAILED, + + CMD_REQUEST_AABB_OVERLAP_COMPLETED, + + CMD_REQUEST_AABB_OVERLAP_FAILED, + + CMD_CALCULATE_INVERSE_KINEMATICS_COMPLETED, + + CMD_CALCULATE_INVERSE_KINEMATICS_FAILED, + + CMD_SAVE_WORLD_COMPLETED, + + CMD_SAVE_WORLD_FAILED, + + CMD_VISUAL_SHAPE_INFO_COMPLETED, + + CMD_VISUAL_SHAPE_INFO_FAILED, + + CMD_VISUAL_SHAPE_UPDATE_COMPLETED, + + CMD_VISUAL_SHAPE_UPDATE_FAILED, + + CMD_LOAD_TEXTURE_COMPLETED, + + CMD_LOAD_TEXTURE_FAILED, + + CMD_USER_DEBUG_DRAW_COMPLETED, + + CMD_USER_DEBUG_DRAW_PARAMETER_COMPLETED, + + CMD_USER_DEBUG_DRAW_FAILED, + + CMD_USER_CONSTRAINT_COMPLETED, + + CMD_USER_CONSTRAINT_INFO_COMPLETED, + + CMD_REMOVE_USER_CONSTRAINT_COMPLETED, + + CMD_CHANGE_USER_CONSTRAINT_COMPLETED, + + CMD_REMOVE_USER_CONSTRAINT_FAILED, + + CMD_CHANGE_USER_CONSTRAINT_FAILED, + + CMD_USER_CONSTRAINT_FAILED, + + CMD_REQUEST_VR_EVENTS_DATA_COMPLETED, + + CMD_REQUEST_RAY_CAST_INTERSECTIONS_COMPLETED, + + CMD_SYNC_BODY_INFO_COMPLETED, + + CMD_SYNC_BODY_INFO_FAILED, + + CMD_STATE_LOGGING_COMPLETED, + + CMD_STATE_LOGGING_START_COMPLETED, + + CMD_STATE_LOGGING_FAILED, + + CMD_REQUEST_KEYBOARD_EVENTS_DATA_COMPLETED, + + CMD_REQUEST_KEYBOARD_EVENTS_DATA_FAILED, + + CMD_REQUEST_OPENGL_VISUALIZER_CAMERA_FAILED, + + CMD_REQUEST_OPENGL_VISUALIZER_CAMERA_COMPLETED, + + CMD_REMOVE_BODY_COMPLETED, + + CMD_REMOVE_BODY_FAILED, + + CMD_GET_DYNAMICS_INFO_COMPLETED, + + CMD_GET_DYNAMICS_INFO_FAILED, + + CMD_CREATE_COLLISION_SHAPE_FAILED, + + CMD_CREATE_COLLISION_SHAPE_COMPLETED, + + CMD_CREATE_VISUAL_SHAPE_FAILED, + + CMD_CREATE_VISUAL_SHAPE_COMPLETED, + + CMD_CREATE_MULTI_BODY_FAILED, + + CMD_CREATE_MULTI_BODY_COMPLETED, + + CMD_REQUEST_COLLISION_INFO_COMPLETED, + + CMD_REQUEST_COLLISION_INFO_FAILED, + + CMD_REQUEST_MOUSE_EVENTS_DATA_COMPLETED, + + CMD_CHANGE_TEXTURE_COMMAND_FAILED, + + CMD_MAX_SERVER_COMMANDS, +} + +public enum JointInfoFlags { + + /// JOINT_HAS_MOTORIZED_POWER -> 1 + JOINT_HAS_MOTORIZED_POWER = 1, +} + +public enum JointType { + + /// eRevoluteType -> 0 + eRevoluteType = 0, + + /// ePrismaticType -> 1 + ePrismaticType = 1, + + /// eSphericalType -> 2 + eSphericalType = 2, + + /// ePlanarType -> 3 + ePlanarType = 3, + + /// eFixedType -> 4 + eFixedType = 4, + + /// ePoint2PointType -> 5 + ePoint2PointType = 5, + + /// eGearType -> 6 + eGearType = 6, +} + +public enum b3JointInfoFlags { + + /// eJointChangeMaxForce -> 1 + eJointChangeMaxForce = 1, + + /// eJointChangeChildFramePosition -> 2 + eJointChangeChildFramePosition = 2, + + /// eJointChangeChildFrameOrientation -> 4 + eJointChangeChildFrameOrientation = 4, +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3JointInfo { + + /// char* + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] + public string m_linkName; + + /// char* + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] + public string m_jointName; + + /// int + public int m_jointType; + + /// int + public int m_qIndex; + + /// int + public int m_uIndex; + + /// int + public int m_jointIndex; + + /// int + public int m_flags; + + /// double + public double m_jointDamping; + + /// double + public double m_jointFriction; + + /// double + public double m_jointLowerLimit; + + /// double + public double m_jointUpperLimit; + + /// double + public double m_jointMaxForce; + + /// double + public double m_jointMaxVelocity; + + /// double[7] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=7, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_parentFrame; + + /// double[7] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=7, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_childFrame; + + /// double[3] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=3, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_jointAxis; +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3UserConstraint { + + /// int + public int m_parentBodyIndex; + + /// int + public int m_parentJointIndex; + + /// int + public int m_childBodyIndex; + + /// int + public int m_childJointIndex; + + /// double[7] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=7, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_parentFrame; + + /// double[7] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=7, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_childFrame; + + /// double[3] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=3, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_jointAxis; + + /// int + public int m_jointType; + + /// double + public double m_maxAppliedForce; + + /// int + public int m_userConstraintUniqueId; + + /// double + public double m_gearRatio; + + /// int + public int m_gearAuxLink; +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3BodyInfo { + + /// char* + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] + public string m_baseName; + + /// char* + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] + public string m_bodyName; +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3DynamicsInfo { + + /// double + public double m_mass; + + /// double[3] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=3, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_localInertialPosition; + + /// double + public double m_lateralFrictionCoeff; +} + +public enum SensorType { + + /// eSensorForceTorqueType -> 1 + eSensorForceTorqueType = 1, +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3JointSensorState { + + /// double + public double m_jointPosition; + + /// double + public double m_jointVelocity; + + /// double[6] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=6, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_jointForceTorque; + + /// double + public double m_jointMotorTorque; +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3DebugLines { + + /// int + public int m_numDebugLines; + + /// float* + public System.IntPtr m_linesFrom; + + /// float* + public System.IntPtr m_linesTo; + + /// float* + public System.IntPtr m_linesColor; +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3OverlappingObject { + + /// int + public int m_objectUniqueId; + + /// int + public int m_linkIndex; +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3AABBOverlapData { + + /// int + public int m_numOverlappingObjects; + + /// b3OverlappingObject* + public System.IntPtr m_overlappingObjects; +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3CameraImageData { + + /// int + public int m_pixelWidth; + + /// int + public int m_pixelHeight; + + /// char* + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] + public string m_rgbColorData; + + /// float* + public System.IntPtr m_depthValues; + + /// int* + public System.IntPtr m_segmentationMaskValues; +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3OpenGLVisualizerCameraInfo { + + /// int + public int m_width; + + /// int + public int m_height; + + /// float[16] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=16, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R4)] + public float[] m_viewMatrix; + + /// float[16] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=16, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R4)] + public float[] m_projectionMatrix; + + /// float[3] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=3, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R4)] + public float[] m_camUp; + + /// float[3] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=3, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R4)] + public float[] m_camForward; + + /// float[3] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=3, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R4)] + public float[] m_horizontal; + + /// float[3] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=3, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R4)] + public float[] m_vertical; + + /// float + public float m_yaw; + + /// float + public float m_pitch; + + /// float + public float m_dist; + + /// float[3] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=3, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R4)] + public float[] m_target; +} + +public enum b3VREventType { + + /// VR_CONTROLLER_MOVE_EVENT -> 1 + VR_CONTROLLER_MOVE_EVENT = 1, + + /// VR_CONTROLLER_BUTTON_EVENT -> 2 + VR_CONTROLLER_BUTTON_EVENT = 2, + + /// VR_HMD_MOVE_EVENT -> 4 + VR_HMD_MOVE_EVENT = 4, + + /// VR_GENERIC_TRACKER_MOVE_EVENT -> 8 + VR_GENERIC_TRACKER_MOVE_EVENT = 8, +} + +public enum b3VRButtonInfo { + + /// eButtonIsDown -> 1 + eButtonIsDown = 1, + + /// eButtonTriggered -> 2 + eButtonTriggered = 2, + + /// eButtonReleased -> 4 + eButtonReleased = 4, +} + +public enum eVRDeviceTypeEnums { + + /// VR_DEVICE_CONTROLLER -> 1 + VR_DEVICE_CONTROLLER = 1, + + /// VR_DEVICE_HMD -> 2 + VR_DEVICE_HMD = 2, + + /// VR_DEVICE_GENERIC_TRACKER -> 4 + VR_DEVICE_GENERIC_TRACKER = 4, +} + +public enum EVRCameraFlags { + + /// VR_CAMERA_TRACK_OBJECT_ORIENTATION -> 1 + VR_CAMERA_TRACK_OBJECT_ORIENTATION = 1, +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3VRControllerEvent { + + /// int + public int m_controllerId; + + /// int + public int m_deviceType; + + /// int + public int m_numMoveEvents; + + /// int + public int m_numButtonEvents; + + /// float[4] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=4, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R4)] + public float[] m_pos; + + /// float[4] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=4, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R4)] + public float[] m_orn; + + /// float + public float m_analogAxis; + + /// int[64] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=64, ArraySubType=System.Runtime.InteropServices.UnmanagedType.I4)] + public int[] m_buttons; +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3VREventsData { + + /// int + public int m_numControllerEvents; + + /// b3VRControllerEvent* + public System.IntPtr m_controllerEvents; +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3KeyboardEvent { + + /// int + public int m_keyCode; + + /// int + public int m_keyState; +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3KeyboardEventsData { + + /// int + public int m_numKeyboardEvents; + + /// b3KeyboardEvent* + public System.IntPtr m_keyboardEvents; +} + +public enum eMouseEventTypeEnums { + + /// MOUSE_MOVE_EVENT -> 1 + MOUSE_MOVE_EVENT = 1, + + /// MOUSE_BUTTON_EVENT -> 2 + MOUSE_BUTTON_EVENT = 2, +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3MouseEvent { + + /// int + public int m_eventType; + + /// float + public float m_mousePosX; + + /// float + public float m_mousePosY; + + /// int + public int m_buttonIndex; + + /// int + public int m_buttonState; +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3MouseEventsData { + + /// int + public int m_numMouseEvents; + + /// b3MouseEvent* + public System.IntPtr m_mouseEvents; +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3ContactPointData { + + /// int + public int m_contactFlags; + + /// int + public int m_bodyUniqueIdA; + + /// int + public int m_bodyUniqueIdB; + + /// int + public int m_linkIndexA; + + /// int + public int m_linkIndexB; + + /// double[3] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=3, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_positionOnAInWS; + + /// double[3] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=3, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_positionOnBInWS; + + /// double[3] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=3, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_contactNormalOnBInWS; + + /// double + public double m_contactDistance; + + /// double + public double m_normalForce; +} + +public enum b3StateLoggingType { + + /// STATE_LOGGING_MINITAUR -> 0 + STATE_LOGGING_MINITAUR = 0, + + /// STATE_LOGGING_GENERIC_ROBOT -> 1 + STATE_LOGGING_GENERIC_ROBOT = 1, + + /// STATE_LOGGING_VR_CONTROLLERS -> 2 + STATE_LOGGING_VR_CONTROLLERS = 2, + + /// STATE_LOGGING_VIDEO_MP4 -> 3 + STATE_LOGGING_VIDEO_MP4 = 3, + + /// STATE_LOGGING_COMMANDS -> 4 + STATE_LOGGING_COMMANDS = 4, + + /// STATE_LOGGING_CONTACT_POINTS -> 5 + STATE_LOGGING_CONTACT_POINTS = 5, + + /// STATE_LOGGING_PROFILE_TIMINGS -> 6 + STATE_LOGGING_PROFILE_TIMINGS = 6, +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3ContactInformation { + + /// int + public int m_numContactPoints; + + /// b3ContactPointData* + public System.IntPtr m_contactPointData; +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3RayHitInfo { + + /// double + public double m_hitFraction; + + /// int + public int m_hitObjectUniqueId; + + /// int + public int m_hitObjectLinkIndex; + + /// double[3] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=3, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_hitPositionWorld; + + /// double[3] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=3, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_hitNormalWorld; +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3RaycastInformation { + + /// int + public int m_numRayHits; + + /// b3RayHitInfo* + public System.IntPtr m_rayHits; +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential, CharSet=System.Runtime.InteropServices.CharSet.Ansi)] +public struct b3VisualShapeData { + + /// int + public int m_objectUniqueId; + + /// int + public int m_linkIndex; + + /// int + public int m_visualGeometryType; + + /// double[3] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=3, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_dimensions; + + /// char[1024] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValTStr, SizeConst=1024)] + public string m_meshAssetFileName; + + /// double[7] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=7, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_localVisualFrame; + + /// double[4] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=4, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_rgbaColor; +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3VisualShapeInformation { + + /// int + public int m_numVisualShapes; + + /// b3VisualShapeData* + public System.IntPtr m_visualShapeData; +} + +public enum eLinkStateFlags { + + /// ACTUAL_STATE_COMPUTE_LINKVELOCITY -> 1 + ACTUAL_STATE_COMPUTE_LINKVELOCITY = 1, +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3LinkState { + + /// double[3] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=3, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_worldPosition; + + /// double[4] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=4, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_worldOrientation; + + /// double[3] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=3, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_localInertialPosition; + + /// double[4] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=4, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_localInertialOrientation; + + /// double[3] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=3, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_worldLinkFramePosition; + + /// double[4] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=4, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_worldLinkFrameOrientation; + + /// double[3] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=3, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_worldLinearVelocity; + + /// double[3] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=3, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_worldAngularVelocity; + + /// double[3] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=3, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_worldAABBMin; + + /// double[3] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=3, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)] + public double[] m_worldAABBMax; +} + +public enum EnumExternalForceFlags { + + /// EF_LINK_FRAME -> 1 + EF_LINK_FRAME = 1, + + /// EF_WORLD_FRAME -> 2 + EF_WORLD_FRAME = 2, +} + +public enum EnumRenderer { + + /// ER_TINY_RENDERER -> (1<<16) + ER_TINY_RENDERER = (1) << (16), + + /// ER_BULLET_HARDWARE_OPENGL -> (1<<17) + ER_BULLET_HARDWARE_OPENGL = (1) << (17), +} + +public enum b3ConfigureDebugVisualizerEnum { + + /// COV_ENABLE_GUI -> 1 + COV_ENABLE_GUI = 1, + + COV_ENABLE_SHADOWS, + + COV_ENABLE_WIREFRAME, + + COV_ENABLE_VR_TELEPORTING, + + COV_ENABLE_VR_PICKING, + + COV_ENABLE_VR_RENDER_CONTROLLERS, + + COV_ENABLE_RENDERING, + + COV_ENABLE_SYNC_RENDERING_INTERNAL, + + COV_ENABLE_KEYBOARD_SHORTCUTS, + + COV_ENABLE_MOUSE_PICKING, +} + +public enum b3AddUserDebugItemEnum { + + /// DEB_DEBUG_TEXT_USE_ORIENTATION -> 1 + DEB_DEBUG_TEXT_USE_ORIENTATION = 1, + + /// DEB_DEBUG_TEXT_USE_TRUE_TYPE_FONTS -> 2 + DEB_DEBUG_TEXT_USE_TRUE_TYPE_FONTS = 2, + + /// DEB_DEBUG_TEXT_HAS_TRACKING_OBJECT -> 4 + DEB_DEBUG_TEXT_HAS_TRACKING_OBJECT = 4, +} + +public enum eCONNECT_METHOD { + + /// eCONNECT_GUI -> 1 + eCONNECT_GUI = 1, + + /// eCONNECT_DIRECT -> 2 + eCONNECT_DIRECT = 2, + + /// eCONNECT_SHARED_MEMORY -> 3 + eCONNECT_SHARED_MEMORY = 3, + + /// eCONNECT_UDP -> 4 + eCONNECT_UDP = 4, + + /// eCONNECT_TCP -> 5 + eCONNECT_TCP = 5, + + /// eCONNECT_EXISTING_EXAMPLE_BROWSER -> 6 + eCONNECT_EXISTING_EXAMPLE_BROWSER = 6, + + /// eCONNECT_GUI_SERVER -> 7 + eCONNECT_GUI_SERVER = 7, +} + +public enum eURDF_Flags { + + /// URDF_USE_INERTIA_FROM_FILE -> 2 + URDF_USE_INERTIA_FROM_FILE = 2, + + /// URDF_USE_SELF_COLLISION -> 8 + URDF_USE_SELF_COLLISION = 8, + + /// URDF_USE_SELF_COLLISION_EXCLUDE_PARENT -> 16 + URDF_USE_SELF_COLLISION_EXCLUDE_PARENT = 16, + + /// URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS -> 32 + URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS = 32, + + /// URDF_RESERVED -> 64 + URDF_RESERVED = 64, +} + +public enum eUrdfGeomTypes { + + /// GEOM_SPHERE -> 2 + GEOM_SPHERE = 2, + + GEOM_BOX, + + GEOM_CYLINDER, + + GEOM_MESH, + + GEOM_PLANE, + + GEOM_CAPSULE, + + GEOM_UNKNOWN, +} + +public enum eUrdfCollisionFlags { + + /// GEOM_FORCE_CONCAVE_TRIMESH -> 1 + GEOM_FORCE_CONCAVE_TRIMESH = 1, +} + +public enum eStateLoggingFlags { + + /// STATE_LOG_JOINT_MOTOR_TORQUES -> 1 + STATE_LOG_JOINT_MOTOR_TORQUES = 1, + + /// STATE_LOG_JOINT_USER_TORQUES -> 2 + STATE_LOG_JOINT_USER_TORQUES = 2, + + /// STATE_LOG_JOINT_TORQUES -> STATE_LOG_JOINT_MOTOR_TORQUES+STATE_LOG_JOINT_USER_TORQUES + STATE_LOG_JOINT_TORQUES = (eStateLoggingFlags.STATE_LOG_JOINT_MOTOR_TORQUES + eStateLoggingFlags.STATE_LOG_JOINT_USER_TORQUES), +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3PhysicsClientHandle__ { + + /// int + public int unused; +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3SharedMemoryCommandHandle__ { + + /// int + public int unused; +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3SharedMemoryStatusHandle__ { + + /// int + public int unused; +} + +public partial class NativeMethods { + + /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///key: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ConnectSharedMemory")] +public static extern System.IntPtr b3ConnectSharedMemory(int key) ; + + + /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///key: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ConnectSharedMemory2")] +public static extern System.IntPtr b3ConnectSharedMemory2(int key) ; + + + /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ConnectPhysicsDirect")] +public static extern System.IntPtr b3ConnectPhysicsDirect() ; + + + /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///argc: int + ///argv: char** + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateInProcessPhysicsServerAndConnect")] +public static extern System.IntPtr b3CreateInProcessPhysicsServerAndConnect(int argc, ref System.IntPtr argv) ; + + + /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///argc: int + ///argv: char** + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateInProcessPhysicsServerAndConnectSharedMemory")] +public static extern System.IntPtr b3CreateInProcessPhysicsServerAndConnectSharedMemory(int argc, ref System.IntPtr argv) ; + + + /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///argc: int + ///argv: char** + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateInProcessPhysicsServerAndConnectMainThread")] +public static extern System.IntPtr b3CreateInProcessPhysicsServerAndConnectMainThread(int argc, ref System.IntPtr argv) ; + + + /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///argc: int + ///argv: char** + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateInProcessPhysicsServerAndConnectMainThreadSharedMemory")] +public static extern System.IntPtr b3CreateInProcessPhysicsServerAndConnectMainThreadSharedMemory(int argc, ref System.IntPtr argv) ; + + + /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///guiHelperPtr: void* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect")] +public static extern System.IntPtr b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect(System.IntPtr guiHelperPtr) ; + + + /// Return Type: void + ///clientHandle: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InProcessRenderSceneInternal")] +public static extern void b3InProcessRenderSceneInternal(ref b3PhysicsClientHandle__ clientHandle) ; + + + /// Return Type: void + ///clientHandle: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///debugDrawMode: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InProcessDebugDrawInternal")] +public static extern void b3InProcessDebugDrawInternal(ref b3PhysicsClientHandle__ clientHandle, int debugDrawMode) ; + + + /// Return Type: int + ///clientHandle: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///x: float + ///y: float + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InProcessMouseMoveCallback")] +public static extern int b3InProcessMouseMoveCallback(ref b3PhysicsClientHandle__ clientHandle, float x, float y) ; + + + /// Return Type: int + ///clientHandle: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///button: int + ///state: int + ///x: float + ///y: float + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InProcessMouseButtonCallback")] +public static extern int b3InProcessMouseButtonCallback(ref b3PhysicsClientHandle__ clientHandle, int button, int state, float x, float y) ; + + + /// Return Type: void + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3DisconnectSharedMemory")] +public static extern void b3DisconnectSharedMemory(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: int + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CanSubmitCommand")] +public static extern int b3CanSubmitCommand(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SubmitClientCommandAndWaitStatus")] +public static extern System.IntPtr b3SubmitClientCommandAndWaitStatus(ref b3PhysicsClientHandle__ physClient, ref b3SharedMemoryCommandHandle__ commandHandle) ; + + + /// Return Type: int + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SubmitClientCommand")] +public static extern int b3SubmitClientCommand(ref b3PhysicsClientHandle__ physClient, ref b3SharedMemoryCommandHandle__ commandHandle) ; + + + /// Return Type: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ProcessServerStatus")] +public static extern System.IntPtr b3ProcessServerStatus(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: int + ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusType")] +public static extern int b3GetStatusType(ref b3SharedMemoryStatusHandle__ statusHandle) ; + + + /// Return Type: int + ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* + ///bodyIndicesOut: int* + ///bodyIndicesCapacity: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusBodyIndices")] +public static extern int b3GetStatusBodyIndices(ref b3SharedMemoryStatusHandle__ statusHandle, ref int bodyIndicesOut, int bodyIndicesCapacity) ; + + + /// Return Type: int + ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusBodyIndex")] +public static extern int b3GetStatusBodyIndex(ref b3SharedMemoryStatusHandle__ statusHandle) ; + + + /// Return Type: int + ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* + ///bodyUniqueId: int* + ///numDegreeOfFreedomQ: int* + ///numDegreeOfFreedomU: int* + ///rootLocalInertialFrame: double** + ///actualStateQ: double** + ///actualStateQdot: double** + ///jointReactionForces: double** + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusActualState")] +public static extern int b3GetStatusActualState(ref b3SharedMemoryStatusHandle__ statusHandle, ref int bodyUniqueId, ref int numDegreeOfFreedomQ, ref int numDegreeOfFreedomU, ref System.IntPtr rootLocalInertialFrame, ref System.IntPtr actualStateQ, ref System.IntPtr actualStateQdot, ref System.IntPtr jointReactionForces) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///bodyUniqueId: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCollisionInfoCommandInit")] +public static extern System.IntPtr b3RequestCollisionInfoCommandInit(ref b3PhysicsClientHandle__ physClient, int bodyUniqueId) ; + + + /// Return Type: int + ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* + ///linkIndex: int + ///aabbMin: double* + ///aabbMax: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusAABB")] +public static extern int b3GetStatusAABB(ref b3SharedMemoryStatusHandle__ statusHandle, int linkIndex, ref double aabbMin, ref double aabbMax) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitSyncBodyInfoCommand")] +public static extern System.IntPtr b3InitSyncBodyInfoCommand(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///bodyUniqueId: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitRemoveBodyCommand")] +public static extern System.IntPtr b3InitRemoveBodyCommand(ref b3PhysicsClientHandle__ physClient, int bodyUniqueId) ; + + + /// Return Type: int + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetNumBodies")] +public static extern int b3GetNumBodies(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: int + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///serialIndex: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetBodyUniqueId")] +public static extern int b3GetBodyUniqueId(ref b3PhysicsClientHandle__ physClient, int serialIndex) ; + + + /// Return Type: int + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///bodyUniqueId: int + ///info: b3BodyInfo* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetBodyInfo")] +public static extern int b3GetBodyInfo(ref b3PhysicsClientHandle__ physClient, int bodyUniqueId, ref b3BodyInfo info) ; + + + /// Return Type: int + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///bodyIndex: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetNumJoints")] +public static extern int b3GetNumJoints(ref b3PhysicsClientHandle__ physClient, int bodyIndex) ; + + + /// Return Type: int + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///bodyIndex: int + ///jointIndex: int + ///info: b3JointInfo* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetJointInfo")] +public static extern int b3GetJointInfo(ref b3PhysicsClientHandle__ physClient, int bodyIndex, int jointIndex, ref b3JointInfo info) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///bodyUniqueId: int + ///linkIndex: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetDynamicsInfoCommandInit")] +public static extern System.IntPtr b3GetDynamicsInfoCommandInit(ref b3PhysicsClientHandle__ physClient, int bodyUniqueId, int linkIndex) ; + + + /// Return Type: int + ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* + ///info: b3DynamicsInfo* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetDynamicsInfo")] +public static extern int b3GetDynamicsInfo(ref b3SharedMemoryStatusHandle__ statusHandle, ref b3DynamicsInfo info) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitChangeDynamicsInfo")] +public static extern System.IntPtr b3InitChangeDynamicsInfo(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///bodyUniqueId: int + ///linkIndex: int + ///mass: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ChangeDynamicsInfoSetMass")] +public static extern int b3ChangeDynamicsInfoSetMass(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueId, int linkIndex, double mass) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///bodyUniqueId: int + ///linkIndex: int + ///lateralFriction: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ChangeDynamicsInfoSetLateralFriction")] +public static extern int b3ChangeDynamicsInfoSetLateralFriction(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueId, int linkIndex, double lateralFriction) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///bodyUniqueId: int + ///linkIndex: int + ///friction: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ChangeDynamicsInfoSetSpinningFriction")] +public static extern int b3ChangeDynamicsInfoSetSpinningFriction(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueId, int linkIndex, double friction) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///bodyUniqueId: int + ///linkIndex: int + ///friction: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ChangeDynamicsInfoSetRollingFriction")] +public static extern int b3ChangeDynamicsInfoSetRollingFriction(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueId, int linkIndex, double friction) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///bodyUniqueId: int + ///linkIndex: int + ///restitution: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ChangeDynamicsInfoSetRestitution")] +public static extern int b3ChangeDynamicsInfoSetRestitution(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueId, int linkIndex, double restitution) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///bodyUniqueId: int + ///linearDamping: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ChangeDynamicsInfoSetLinearDamping")] +public static extern int b3ChangeDynamicsInfoSetLinearDamping(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueId, double linearDamping) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///bodyUniqueId: int + ///angularDamping: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ChangeDynamicsInfoSetAngularDamping")] +public static extern int b3ChangeDynamicsInfoSetAngularDamping(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueId, double angularDamping) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///bodyUniqueId: int + ///linkIndex: int + ///contactStiffness: double + ///contactDamping: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ChangeDynamicsInfoSetContactStiffnessAndDamping")] +public static extern int b3ChangeDynamicsInfoSetContactStiffnessAndDamping(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueId, int linkIndex, double contactStiffness, double contactDamping) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///bodyUniqueId: int + ///linkIndex: int + ///frictionAnchor: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ChangeDynamicsInfoSetFrictionAnchor")] +public static extern int b3ChangeDynamicsInfoSetFrictionAnchor(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueId, int linkIndex, int frictionAnchor) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///parentBodyIndex: int + ///parentJointIndex: int + ///childBodyIndex: int + ///childJointIndex: int + ///info: b3JointInfo* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitCreateUserConstraintCommand")] +public static extern System.IntPtr b3InitCreateUserConstraintCommand(ref b3PhysicsClientHandle__ physClient, int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, ref b3JointInfo info) ; + + + /// Return Type: int + ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusUserConstraintUniqueId")] +public static extern int b3GetStatusUserConstraintUniqueId(ref b3SharedMemoryStatusHandle__ statusHandle) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///userConstraintUniqueId: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitChangeUserConstraintCommand")] +public static extern System.IntPtr b3InitChangeUserConstraintCommand(ref b3PhysicsClientHandle__ physClient, int userConstraintUniqueId) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///jointChildPivot: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitChangeUserConstraintSetPivotInB")] +public static extern int b3InitChangeUserConstraintSetPivotInB(ref b3SharedMemoryCommandHandle__ commandHandle, ref double jointChildPivot) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///jointChildFrameOrn: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitChangeUserConstraintSetFrameInB")] +public static extern int b3InitChangeUserConstraintSetFrameInB(ref b3SharedMemoryCommandHandle__ commandHandle, ref double jointChildFrameOrn) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///maxAppliedForce: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitChangeUserConstraintSetMaxForce")] +public static extern int b3InitChangeUserConstraintSetMaxForce(ref b3SharedMemoryCommandHandle__ commandHandle, double maxAppliedForce) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///gearRatio: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitChangeUserConstraintSetGearRatio")] +public static extern int b3InitChangeUserConstraintSetGearRatio(ref b3SharedMemoryCommandHandle__ commandHandle, double gearRatio) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///gearAuxLink: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitChangeUserConstraintSetGearAuxLink")] +public static extern int b3InitChangeUserConstraintSetGearAuxLink(ref b3SharedMemoryCommandHandle__ commandHandle, int gearAuxLink) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///userConstraintUniqueId: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitRemoveUserConstraintCommand")] +public static extern System.IntPtr b3InitRemoveUserConstraintCommand(ref b3PhysicsClientHandle__ physClient, int userConstraintUniqueId) ; + + + /// Return Type: int + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetNumUserConstraints")] +public static extern int b3GetNumUserConstraints(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: int + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///constraintUniqueId: int + ///info: b3UserConstraint* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetUserConstraintInfo")] +public static extern int b3GetUserConstraintInfo(ref b3PhysicsClientHandle__ physClient, int constraintUniqueId, ref b3UserConstraint info) ; + + + /// Return Type: int + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///serialIndex: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetUserConstraintId")] +public static extern int b3GetUserConstraintId(ref b3PhysicsClientHandle__ physClient, int serialIndex) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///debugMode: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitRequestDebugLinesCommand")] +public static extern System.IntPtr b3InitRequestDebugLinesCommand(ref b3PhysicsClientHandle__ physClient, int debugMode) ; + + + /// Return Type: void + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///lines: b3DebugLines* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetDebugLines")] +public static extern void b3GetDebugLines(ref b3PhysicsClientHandle__ physClient, ref b3DebugLines lines) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitConfigureOpenGLVisualizer")] +public static extern System.IntPtr b3InitConfigureOpenGLVisualizer(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///flag: int + ///enabled: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ConfigureOpenGLVisualizerSetVisualizationFlags")] +public static extern void b3ConfigureOpenGLVisualizerSetVisualizationFlags(ref b3SharedMemoryCommandHandle__ commandHandle, int flag, int enabled) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///cameraDistance: float + ///cameraPitch: float + ///cameraYaw: float + ///cameraTargetPosition: float* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ConfigureOpenGLVisualizerSetViewMatrix")] +public static extern void b3ConfigureOpenGLVisualizerSetViewMatrix(ref b3SharedMemoryCommandHandle__ commandHandle, float cameraDistance, float cameraPitch, float cameraYaw, ref float cameraTargetPosition) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitRequestOpenGLVisualizerCameraCommand")] +public static extern System.IntPtr b3InitRequestOpenGLVisualizerCameraCommand(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: int + ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* + ///camera: b3OpenGLVisualizerCameraInfo* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusOpenGLVisualizerCamera")] +public static extern int b3GetStatusOpenGLVisualizerCamera(ref b3SharedMemoryStatusHandle__ statusHandle, ref b3OpenGLVisualizerCameraInfo camera) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///fromXYZ: double* + ///toXYZ: double* + ///colorRGB: double* + ///lineWidth: double + ///lifeTime: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitUserDebugDrawAddLine3D")] +public static extern System.IntPtr b3InitUserDebugDrawAddLine3D(ref b3PhysicsClientHandle__ physClient, ref double fromXYZ, ref double toXYZ, ref double colorRGB, double lineWidth, double lifeTime) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///txt: char* + ///positionXYZ: double* + ///colorRGB: double* + ///textSize: double + ///lifeTime: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitUserDebugDrawAddText3D")] +public static extern System.IntPtr b3InitUserDebugDrawAddText3D(ref b3PhysicsClientHandle__ physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string txt, ref double positionXYZ, ref double colorRGB, double textSize, double lifeTime) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///optionFlags: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3UserDebugTextSetOptionFlags")] +public static extern void b3UserDebugTextSetOptionFlags(ref b3SharedMemoryCommandHandle__ commandHandle, int optionFlags) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///orientation: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3UserDebugTextSetOrientation")] +public static extern void b3UserDebugTextSetOrientation(ref b3SharedMemoryCommandHandle__ commandHandle, ref double orientation) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///objectUniqueId: int + ///linkIndex: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3UserDebugItemSetParentObject")] +public static extern void b3UserDebugItemSetParentObject(ref b3SharedMemoryCommandHandle__ commandHandle, int objectUniqueId, int linkIndex) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///txt: char* + ///rangeMin: double + ///rangeMax: double + ///startValue: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitUserDebugAddParameter")] +public static extern System.IntPtr b3InitUserDebugAddParameter(ref b3PhysicsClientHandle__ physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string txt, double rangeMin, double rangeMax, double startValue) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///debugItemUniqueId: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitUserDebugReadParameter")] +public static extern System.IntPtr b3InitUserDebugReadParameter(ref b3PhysicsClientHandle__ physClient, int debugItemUniqueId) ; + + + /// Return Type: int + ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* + ///paramValue: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusDebugParameterValue")] +public static extern int b3GetStatusDebugParameterValue(ref b3SharedMemoryStatusHandle__ statusHandle, ref double paramValue) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///debugItemUniqueId: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitUserDebugDrawRemove")] +public static extern System.IntPtr b3InitUserDebugDrawRemove(ref b3PhysicsClientHandle__ physClient, int debugItemUniqueId) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitUserDebugDrawRemoveAll")] +public static extern System.IntPtr b3InitUserDebugDrawRemoveAll(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitDebugDrawingCommand")] +public static extern System.IntPtr b3InitDebugDrawingCommand(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///objectUniqueId: int + ///linkIndex: int + ///objectColorRGB: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetDebugObjectColor")] +public static extern void b3SetDebugObjectColor(ref b3SharedMemoryCommandHandle__ commandHandle, int objectUniqueId, int linkIndex, ref double objectColorRGB) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///objectUniqueId: int + ///linkIndex: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RemoveDebugObjectColor")] +public static extern void b3RemoveDebugObjectColor(ref b3SharedMemoryCommandHandle__ commandHandle, int objectUniqueId, int linkIndex) ; + + + /// Return Type: int + ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetDebugItemUniqueId")] +public static extern int b3GetDebugItemUniqueId(ref b3SharedMemoryStatusHandle__ statusHandle) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitRequestCameraImage")] +public static extern System.IntPtr b3InitRequestCameraImage(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: void + ///command: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///viewMatrix: float* + ///projectionMatrix: float* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetCameraMatrices")] +public static extern void b3RequestCameraImageSetCameraMatrices(ref b3SharedMemoryCommandHandle__ command, ref float viewMatrix, ref float projectionMatrix) ; + + + /// Return Type: void + ///command: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///width: int + ///height: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetPixelResolution")] +public static extern void b3RequestCameraImageSetPixelResolution(ref b3SharedMemoryCommandHandle__ command, int width, int height) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///lightDirection: float* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetLightDirection")] +public static extern void b3RequestCameraImageSetLightDirection(ref b3SharedMemoryCommandHandle__ commandHandle, ref float lightDirection) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///lightColor: float* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetLightColor")] +public static extern void b3RequestCameraImageSetLightColor(ref b3SharedMemoryCommandHandle__ commandHandle, ref float lightColor) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///lightDistance: float + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetLightDistance")] +public static extern void b3RequestCameraImageSetLightDistance(ref b3SharedMemoryCommandHandle__ commandHandle, float lightDistance) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///lightAmbientCoeff: float + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetLightAmbientCoeff")] +public static extern void b3RequestCameraImageSetLightAmbientCoeff(ref b3SharedMemoryCommandHandle__ commandHandle, float lightAmbientCoeff) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///lightDiffuseCoeff: float + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetLightDiffuseCoeff")] +public static extern void b3RequestCameraImageSetLightDiffuseCoeff(ref b3SharedMemoryCommandHandle__ commandHandle, float lightDiffuseCoeff) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///lightSpecularCoeff: float + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetLightSpecularCoeff")] +public static extern void b3RequestCameraImageSetLightSpecularCoeff(ref b3SharedMemoryCommandHandle__ commandHandle, float lightSpecularCoeff) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///hasShadow: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetShadow")] +public static extern void b3RequestCameraImageSetShadow(ref b3SharedMemoryCommandHandle__ commandHandle, int hasShadow) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///renderer: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSelectRenderer")] +public static extern void b3RequestCameraImageSelectRenderer(ref b3SharedMemoryCommandHandle__ commandHandle, int renderer) ; + + + /// Return Type: void + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///imageData: b3CameraImageData* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetCameraImageData")] +public static extern void b3GetCameraImageData(ref b3PhysicsClientHandle__ physClient, ref b3CameraImageData imageData) ; + + + /// Return Type: void + ///cameraPosition: float* + ///cameraTargetPosition: float* + ///cameraUp: float* + ///viewMatrix: float* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ComputeViewMatrixFromPositions")] +public static extern void b3ComputeViewMatrixFromPositions(ref float cameraPosition, ref float cameraTargetPosition, ref float cameraUp, ref float viewMatrix) ; + + + /// Return Type: void + ///cameraTargetPosition: float* + ///distance: float + ///yaw: float + ///pitch: float + ///roll: float + ///upAxis: int + ///viewMatrix: float* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ComputeViewMatrixFromYawPitchRoll")] +public static extern void b3ComputeViewMatrixFromYawPitchRoll(ref float cameraTargetPosition, float distance, float yaw, float pitch, float roll, int upAxis, ref float viewMatrix) ; + + + /// Return Type: void + ///viewMatrix: float* + ///cameraPosition: float* + ///cameraTargetPosition: float* + ///cameraUp: float* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ComputePositionFromViewMatrix")] +public static extern void b3ComputePositionFromViewMatrix(ref float viewMatrix, ref float cameraPosition, ref float cameraTargetPosition, ref float cameraUp) ; + + + /// Return Type: void + ///left: float + ///right: float + ///bottom: float + ///top: float + ///nearVal: float + ///farVal: float + ///projectionMatrix: float* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ComputeProjectionMatrix")] +public static extern void b3ComputeProjectionMatrix(float left, float right, float bottom, float top, float nearVal, float farVal, ref float projectionMatrix) ; + + + /// Return Type: void + ///fov: float + ///aspect: float + ///nearVal: float + ///farVal: float + ///projectionMatrix: float* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ComputeProjectionMatrixFOV")] +public static extern void b3ComputeProjectionMatrixFOV(float fov, float aspect, float nearVal, float farVal, ref float projectionMatrix) ; + + + /// Return Type: void + ///command: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///cameraPosition: float* + ///cameraTargetPosition: float* + ///cameraUp: float* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetViewMatrix")] +public static extern void b3RequestCameraImageSetViewMatrix(ref b3SharedMemoryCommandHandle__ command, ref float cameraPosition, ref float cameraTargetPosition, ref float cameraUp) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///cameraTargetPosition: float* + ///distance: float + ///yaw: float + ///pitch: float + ///roll: float + ///upAxis: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetViewMatrix2")] +public static extern void b3RequestCameraImageSetViewMatrix2(ref b3SharedMemoryCommandHandle__ commandHandle, ref float cameraTargetPosition, float distance, float yaw, float pitch, float roll, int upAxis) ; + + + /// Return Type: void + ///command: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///left: float + ///right: float + ///bottom: float + ///top: float + ///nearVal: float + ///farVal: float + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetProjectionMatrix")] +public static extern void b3RequestCameraImageSetProjectionMatrix(ref b3SharedMemoryCommandHandle__ command, float left, float right, float bottom, float top, float nearVal, float farVal) ; + + + /// Return Type: void + ///command: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///fov: float + ///aspect: float + ///nearVal: float + ///farVal: float + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestCameraImageSetFOVProjectionMatrix")] +public static extern void b3RequestCameraImageSetFOVProjectionMatrix(ref b3SharedMemoryCommandHandle__ command, float fov, float aspect, float nearVal, float farVal) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitRequestContactPointInformation")] +public static extern System.IntPtr b3InitRequestContactPointInformation(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///bodyUniqueIdA: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetContactFilterBodyA")] +public static extern void b3SetContactFilterBodyA(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueIdA) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///bodyUniqueIdB: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetContactFilterBodyB")] +public static extern void b3SetContactFilterBodyB(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueIdB) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///linkIndexA: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetContactFilterLinkA")] +public static extern void b3SetContactFilterLinkA(ref b3SharedMemoryCommandHandle__ commandHandle, int linkIndexA) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///linkIndexB: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetContactFilterLinkB")] +public static extern void b3SetContactFilterLinkB(ref b3SharedMemoryCommandHandle__ commandHandle, int linkIndexB) ; + + + /// Return Type: void + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///contactPointInfo: b3ContactInformation* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetContactPointInformation")] +public static extern void b3GetContactPointInformation(ref b3PhysicsClientHandle__ physClient, ref b3ContactInformation contactPointInfo) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitClosestDistanceQuery")] +public static extern System.IntPtr b3InitClosestDistanceQuery(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///bodyUniqueIdA: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetClosestDistanceFilterBodyA")] +public static extern void b3SetClosestDistanceFilterBodyA(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueIdA) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///linkIndexA: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetClosestDistanceFilterLinkA")] +public static extern void b3SetClosestDistanceFilterLinkA(ref b3SharedMemoryCommandHandle__ commandHandle, int linkIndexA) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///bodyUniqueIdB: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetClosestDistanceFilterBodyB")] +public static extern void b3SetClosestDistanceFilterBodyB(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueIdB) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///linkIndexB: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetClosestDistanceFilterLinkB")] +public static extern void b3SetClosestDistanceFilterLinkB(ref b3SharedMemoryCommandHandle__ commandHandle, int linkIndexB) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///distance: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetClosestDistanceThreshold")] +public static extern void b3SetClosestDistanceThreshold(ref b3SharedMemoryCommandHandle__ commandHandle, double distance) ; + + + /// Return Type: void + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///contactPointInfo: b3ContactInformation* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetClosestPointInformation")] +public static extern void b3GetClosestPointInformation(ref b3PhysicsClientHandle__ physClient, ref b3ContactInformation contactPointInfo) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///aabbMin: double* + ///aabbMax: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitAABBOverlapQuery")] +public static extern System.IntPtr b3InitAABBOverlapQuery(ref b3PhysicsClientHandle__ physClient, ref double aabbMin, ref double aabbMax) ; + + + /// Return Type: void + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///data: b3AABBOverlapData* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetAABBOverlapResults")] +public static extern void b3GetAABBOverlapResults(ref b3PhysicsClientHandle__ physClient, ref b3AABBOverlapData data) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///bodyUniqueIdA: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitRequestVisualShapeInformation")] +public static extern System.IntPtr b3InitRequestVisualShapeInformation(ref b3PhysicsClientHandle__ physClient, int bodyUniqueIdA) ; + + + /// Return Type: void + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///visualShapeInfo: b3VisualShapeInformation* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetVisualShapeInformation")] +public static extern void b3GetVisualShapeInformation(ref b3PhysicsClientHandle__ physClient, ref b3VisualShapeInformation visualShapeInfo) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///filename: char* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitLoadTexture")] +public static extern System.IntPtr b3InitLoadTexture(ref b3PhysicsClientHandle__ physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string filename) ; + + + /// Return Type: int + ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusTextureUniqueId")] +public static extern int b3GetStatusTextureUniqueId(ref b3SharedMemoryStatusHandle__ statusHandle) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///textureUniqueId: int + ///width: int + ///height: int + ///rgbPixels: char* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateChangeTextureCommandInit")] +public static extern System.IntPtr b3CreateChangeTextureCommandInit(ref b3PhysicsClientHandle__ physClient, int textureUniqueId, int width, int height, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string rgbPixels) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///bodyUniqueId: int + ///jointIndex: int + ///shapeIndex: int + ///textureUniqueId: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitUpdateVisualShape")] +public static extern System.IntPtr b3InitUpdateVisualShape(ref b3PhysicsClientHandle__ physClient, int bodyUniqueId, int jointIndex, int shapeIndex, int textureUniqueId) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///rgbaColor: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3UpdateVisualShapeRGBAColor")] +public static extern void b3UpdateVisualShapeRGBAColor(ref b3SharedMemoryCommandHandle__ commandHandle, ref double rgbaColor) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///specularColor: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3UpdateVisualShapeSpecularColor")] +public static extern void b3UpdateVisualShapeSpecularColor(ref b3SharedMemoryCommandHandle__ commandHandle, ref double specularColor) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitPhysicsParamCommand")] +public static extern System.IntPtr b3InitPhysicsParamCommand(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///gravx: double + ///gravy: double + ///gravz: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetGravity")] +public static extern int b3PhysicsParamSetGravity(ref b3SharedMemoryCommandHandle__ commandHandle, double gravx, double gravy, double gravz) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///timeStep: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetTimeStep")] +public static extern int b3PhysicsParamSetTimeStep(ref b3SharedMemoryCommandHandle__ commandHandle, double timeStep) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///defaultContactERP: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetDefaultContactERP")] +public static extern int b3PhysicsParamSetDefaultContactERP(ref b3SharedMemoryCommandHandle__ commandHandle, double defaultContactERP) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///defaultNonContactERP: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetDefaultNonContactERP")] +public static extern int b3PhysicsParamSetDefaultNonContactERP(ref b3SharedMemoryCommandHandle__ commandHandle, double defaultNonContactERP) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///frictionERP: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetDefaultFrictionERP")] +public static extern int b3PhysicsParamSetDefaultFrictionERP(ref b3SharedMemoryCommandHandle__ commandHandle, double frictionERP) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///numSubSteps: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetNumSubSteps")] +public static extern int b3PhysicsParamSetNumSubSteps(ref b3SharedMemoryCommandHandle__ commandHandle, int numSubSteps) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///enableRealTimeSimulation: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetRealTimeSimulation")] +public static extern int b3PhysicsParamSetRealTimeSimulation(ref b3SharedMemoryCommandHandle__ commandHandle, int enableRealTimeSimulation) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///numSolverIterations: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetNumSolverIterations")] +public static extern int b3PhysicsParamSetNumSolverIterations(ref b3SharedMemoryCommandHandle__ commandHandle, int numSolverIterations) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///filterMode: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetCollisionFilterMode")] +public static extern int b3PhysicsParamSetCollisionFilterMode(ref b3SharedMemoryCommandHandle__ commandHandle, int filterMode) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///useSplitImpulse: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetUseSplitImpulse")] +public static extern int b3PhysicsParamSetUseSplitImpulse(ref b3SharedMemoryCommandHandle__ commandHandle, int useSplitImpulse) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///splitImpulsePenetrationThreshold: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetSplitImpulsePenetrationThreshold")] +public static extern int b3PhysicsParamSetSplitImpulsePenetrationThreshold(ref b3SharedMemoryCommandHandle__ commandHandle, double splitImpulsePenetrationThreshold) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///contactBreakingThreshold: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetContactBreakingThreshold")] +public static extern int b3PhysicsParamSetContactBreakingThreshold(ref b3SharedMemoryCommandHandle__ commandHandle, double contactBreakingThreshold) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///maxNumCmdPer1ms: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetMaxNumCommandsPer1ms")] +public static extern int b3PhysicsParamSetMaxNumCommandsPer1ms(ref b3SharedMemoryCommandHandle__ commandHandle, int maxNumCmdPer1ms) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///enableFileCaching: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetEnableFileCaching")] +public static extern int b3PhysicsParamSetEnableFileCaching(ref b3SharedMemoryCommandHandle__ commandHandle, int enableFileCaching) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///restitutionVelocityThreshold: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetRestitutionVelocityThreshold")] +public static extern int b3PhysicsParamSetRestitutionVelocityThreshold(ref b3SharedMemoryCommandHandle__ commandHandle, double restitutionVelocityThreshold) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///flags: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PhysicsParamSetInternalSimFlags")] +public static extern int b3PhysicsParamSetInternalSimFlags(ref b3SharedMemoryCommandHandle__ commandHandle, int flags) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitStepSimulationCommand")] +public static extern System.IntPtr b3InitStepSimulationCommand(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3InitResetSimulationCommand")] +public static extern System.IntPtr b3InitResetSimulationCommand(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///urdfFileName: char* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadUrdfCommandInit")] +public static extern System.IntPtr b3LoadUrdfCommandInit(ref b3PhysicsClientHandle__ physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string urdfFileName) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///startPosX: double + ///startPosY: double + ///startPosZ: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadUrdfCommandSetStartPosition")] +public static extern int b3LoadUrdfCommandSetStartPosition(ref b3SharedMemoryCommandHandle__ commandHandle, double startPosX, double startPosY, double startPosZ) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///startOrnX: double + ///startOrnY: double + ///startOrnZ: double + ///startOrnW: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadUrdfCommandSetStartOrientation")] +public static extern int b3LoadUrdfCommandSetStartOrientation(ref b3SharedMemoryCommandHandle__ commandHandle, double startOrnX, double startOrnY, double startOrnZ, double startOrnW) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///useMultiBody: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadUrdfCommandSetUseMultiBody")] +public static extern int b3LoadUrdfCommandSetUseMultiBody(ref b3SharedMemoryCommandHandle__ commandHandle, int useMultiBody) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///useFixedBase: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadUrdfCommandSetUseFixedBase")] +public static extern int b3LoadUrdfCommandSetUseFixedBase(ref b3SharedMemoryCommandHandle__ commandHandle, int useFixedBase) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///flags: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadUrdfCommandSetFlags")] +public static extern int b3LoadUrdfCommandSetFlags(ref b3SharedMemoryCommandHandle__ commandHandle, int flags) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///globalScaling: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadUrdfCommandSetGlobalScaling")] +public static extern int b3LoadUrdfCommandSetGlobalScaling(ref b3SharedMemoryCommandHandle__ commandHandle, double globalScaling) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///fileName: char* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadBulletCommandInit")] +public static extern System.IntPtr b3LoadBulletCommandInit(ref b3PhysicsClientHandle__ physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///fileName: char* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SaveBulletCommandInit")] +public static extern System.IntPtr b3SaveBulletCommandInit(ref b3PhysicsClientHandle__ physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///fileName: char* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadMJCFCommandInit")] +public static extern System.IntPtr b3LoadMJCFCommandInit(ref b3PhysicsClientHandle__ physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///flags: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadMJCFCommandSetFlags")] +public static extern void b3LoadMJCFCommandSetFlags(ref b3SharedMemoryCommandHandle__ commandHandle, int flags) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///bodyIndex: int + ///jointPositionsQ: double* + ///jointVelocitiesQdot: double* + ///jointAccelerations: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CalculateInverseDynamicsCommandInit")] +public static extern System.IntPtr b3CalculateInverseDynamicsCommandInit(ref b3PhysicsClientHandle__ physClient, int bodyIndex, ref double jointPositionsQ, ref double jointVelocitiesQdot, ref double jointAccelerations) ; + + + /// Return Type: int + ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* + ///bodyUniqueId: int* + ///dofCount: int* + ///jointForces: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusInverseDynamicsJointForces")] +public static extern int b3GetStatusInverseDynamicsJointForces(ref b3SharedMemoryStatusHandle__ statusHandle, ref int bodyUniqueId, ref int dofCount, ref double jointForces) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///bodyIndex: int + ///linkIndex: int + ///localPosition: double* + ///jointPositionsQ: double* + ///jointVelocitiesQdot: double* + ///jointAccelerations: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CalculateJacobianCommandInit")] +public static extern System.IntPtr b3CalculateJacobianCommandInit(ref b3PhysicsClientHandle__ physClient, int bodyIndex, int linkIndex, ref double localPosition, ref double jointPositionsQ, ref double jointVelocitiesQdot, ref double jointAccelerations) ; + + + /// Return Type: int + ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* + ///linearJacobian: double* + ///angularJacobian: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusJacobian")] +public static extern int b3GetStatusJacobian(ref b3SharedMemoryStatusHandle__ statusHandle, ref double linearJacobian, ref double angularJacobian) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///bodyIndex: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CalculateInverseKinematicsCommandInit")] +public static extern System.IntPtr b3CalculateInverseKinematicsCommandInit(ref b3PhysicsClientHandle__ physClient, int bodyIndex) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///endEffectorLinkIndex: int + ///targetPosition: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CalculateInverseKinematicsAddTargetPurePosition")] +public static extern void b3CalculateInverseKinematicsAddTargetPurePosition(ref b3SharedMemoryCommandHandle__ commandHandle, int endEffectorLinkIndex, ref double targetPosition) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///endEffectorLinkIndex: int + ///targetPosition: double* + ///targetOrientation: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CalculateInverseKinematicsAddTargetPositionWithOrientation")] +public static extern void b3CalculateInverseKinematicsAddTargetPositionWithOrientation(ref b3SharedMemoryCommandHandle__ commandHandle, int endEffectorLinkIndex, ref double targetPosition, ref double targetOrientation) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///numDof: int + ///endEffectorLinkIndex: int + ///targetPosition: double* + ///lowerLimit: double* + ///upperLimit: double* + ///jointRange: double* + ///restPose: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CalculateInverseKinematicsPosWithNullSpaceVel")] +public static extern void b3CalculateInverseKinematicsPosWithNullSpaceVel(ref b3SharedMemoryCommandHandle__ commandHandle, int numDof, int endEffectorLinkIndex, ref double targetPosition, ref double lowerLimit, ref double upperLimit, ref double jointRange, ref double restPose) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///numDof: int + ///endEffectorLinkIndex: int + ///targetPosition: double* + ///targetOrientation: double* + ///lowerLimit: double* + ///upperLimit: double* + ///jointRange: double* + ///restPose: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CalculateInverseKinematicsPosOrnWithNullSpaceVel")] +public static extern void b3CalculateInverseKinematicsPosOrnWithNullSpaceVel(ref b3SharedMemoryCommandHandle__ commandHandle, int numDof, int endEffectorLinkIndex, ref double targetPosition, ref double targetOrientation, ref double lowerLimit, ref double upperLimit, ref double jointRange, ref double restPose) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///numDof: int + ///jointDampingCoeff: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CalculateInverseKinematicsSetJointDamping")] +public static extern void b3CalculateInverseKinematicsSetJointDamping(ref b3SharedMemoryCommandHandle__ commandHandle, int numDof, ref double jointDampingCoeff) ; + + + /// Return Type: int + ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* + ///bodyUniqueId: int* + ///dofCount: int* + ///jointPositions: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusInverseKinematicsJointPositions")] +public static extern int b3GetStatusInverseKinematicsJointPositions(ref b3SharedMemoryStatusHandle__ statusHandle, ref int bodyUniqueId, ref int dofCount, ref double jointPositions) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///sdfFileName: char* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadSdfCommandInit")] +public static extern System.IntPtr b3LoadSdfCommandInit(ref b3PhysicsClientHandle__ physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string sdfFileName) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///useMultiBody: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadSdfCommandSetUseMultiBody")] +public static extern int b3LoadSdfCommandSetUseMultiBody(ref b3SharedMemoryCommandHandle__ commandHandle, int useMultiBody) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///globalScaling: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadSdfCommandSetUseGlobalScaling")] +public static extern int b3LoadSdfCommandSetUseGlobalScaling(ref b3SharedMemoryCommandHandle__ commandHandle, double globalScaling) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///sdfFileName: char* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SaveWorldCommandInit")] +public static extern System.IntPtr b3SaveWorldCommandInit(ref b3PhysicsClientHandle__ physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string sdfFileName) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///controlMode: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3JointControlCommandInit")] +public static extern System.IntPtr b3JointControlCommandInit(ref b3PhysicsClientHandle__ physClient, int controlMode) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///bodyUniqueId: int + ///controlMode: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3JointControlCommandInit2")] +public static extern System.IntPtr b3JointControlCommandInit2(ref b3PhysicsClientHandle__ physClient, int bodyUniqueId, int controlMode) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///qIndex: int + ///value: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3JointControlSetDesiredPosition")] +public static extern int b3JointControlSetDesiredPosition(ref b3SharedMemoryCommandHandle__ commandHandle, int qIndex, double value) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///dofIndex: int + ///value: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3JointControlSetKp")] +public static extern int b3JointControlSetKp(ref b3SharedMemoryCommandHandle__ commandHandle, int dofIndex, double value) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///dofIndex: int + ///value: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3JointControlSetKd")] +public static extern int b3JointControlSetKd(ref b3SharedMemoryCommandHandle__ commandHandle, int dofIndex, double value) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///dofIndex: int + ///value: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3JointControlSetDesiredVelocity")] +public static extern int b3JointControlSetDesiredVelocity(ref b3SharedMemoryCommandHandle__ commandHandle, int dofIndex, double value) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///dofIndex: int + ///value: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3JointControlSetMaximumForce")] +public static extern int b3JointControlSetMaximumForce(ref b3SharedMemoryCommandHandle__ commandHandle, int dofIndex, double value) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///dofIndex: int + ///value: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3JointControlSetDesiredForceTorque")] +public static extern int b3JointControlSetDesiredForceTorque(ref b3SharedMemoryCommandHandle__ commandHandle, int dofIndex, double value) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateCollisionShapeCommandInit")] +public static extern System.IntPtr b3CreateCollisionShapeCommandInit(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///radius: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateCollisionShapeAddSphere")] +public static extern int b3CreateCollisionShapeAddSphere(ref b3SharedMemoryCommandHandle__ commandHandle, double radius) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///halfExtents: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateCollisionShapeAddBox")] +public static extern int b3CreateCollisionShapeAddBox(ref b3SharedMemoryCommandHandle__ commandHandle, ref double halfExtents) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///radius: double + ///height: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateCollisionShapeAddCapsule")] +public static extern int b3CreateCollisionShapeAddCapsule(ref b3SharedMemoryCommandHandle__ commandHandle, double radius, double height) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///radius: double + ///height: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateCollisionShapeAddCylinder")] +public static extern int b3CreateCollisionShapeAddCylinder(ref b3SharedMemoryCommandHandle__ commandHandle, double radius, double height) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///planeNormal: double* + ///planeConstant: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateCollisionShapeAddPlane")] +public static extern int b3CreateCollisionShapeAddPlane(ref b3SharedMemoryCommandHandle__ commandHandle, ref double planeNormal, double planeConstant) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///fileName: char* + ///meshScale: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateCollisionShapeAddMesh")] +public static extern int b3CreateCollisionShapeAddMesh(ref b3SharedMemoryCommandHandle__ commandHandle, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName, ref double meshScale) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///shapeIndex: int + ///flags: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateCollisionSetFlag")] +public static extern void b3CreateCollisionSetFlag(ref b3SharedMemoryCommandHandle__ commandHandle, int shapeIndex, int flags) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///shapeIndex: int + ///childPosition: double* + ///childOrientation: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateCollisionShapeSetChildTransform")] +public static extern void b3CreateCollisionShapeSetChildTransform(ref b3SharedMemoryCommandHandle__ commandHandle, int shapeIndex, ref double childPosition, ref double childOrientation) ; + + + /// Return Type: int + ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusCollisionShapeUniqueId")] +public static extern int b3GetStatusCollisionShapeUniqueId(ref b3SharedMemoryStatusHandle__ statusHandle) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateVisualShapeCommandInit")] +public static extern System.IntPtr b3CreateVisualShapeCommandInit(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: int + ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusVisualShapeUniqueId")] +public static extern int b3GetStatusVisualShapeUniqueId(ref b3SharedMemoryStatusHandle__ statusHandle) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateMultiBodyCommandInit")] +public static extern System.IntPtr b3CreateMultiBodyCommandInit(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///mass: double + ///collisionShapeUnique: int + ///visualShapeUniqueId: int + ///basePosition: double* + ///baseOrientation: double* + ///baseInertialFramePosition: double* + ///baseInertialFrameOrientation: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateMultiBodyBase")] +public static extern int b3CreateMultiBodyBase(ref b3SharedMemoryCommandHandle__ commandHandle, double mass, int collisionShapeUnique, int visualShapeUniqueId, ref double basePosition, ref double baseOrientation, ref double baseInertialFramePosition, ref double baseInertialFrameOrientation) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///linkMass: double + ///linkCollisionShapeIndex: double + ///linkVisualShapeIndex: double + ///linkPosition: double* + ///linkOrientation: double* + ///linkInertialFramePosition: double* + ///linkInertialFrameOrientation: double* + ///linkParentIndex: int + ///linkJointType: int + ///linkJointAxis: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateMultiBodyLink")] +public static extern int b3CreateMultiBodyLink(ref b3SharedMemoryCommandHandle__ commandHandle, double linkMass, double linkCollisionShapeIndex, double linkVisualShapeIndex, ref double linkPosition, ref double linkOrientation, ref double linkInertialFramePosition, ref double linkInertialFrameOrientation, int linkParentIndex, int linkJointType, ref double linkJointAxis) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateMultiBodyUseMaximalCoordinates")] +public static extern void b3CreateMultiBodyUseMaximalCoordinates(ref b3SharedMemoryCommandHandle__ commandHandle) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateBoxShapeCommandInit")] +public static extern System.IntPtr b3CreateBoxShapeCommandInit(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///startPosX: double + ///startPosY: double + ///startPosZ: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateBoxCommandSetStartPosition")] +public static extern int b3CreateBoxCommandSetStartPosition(ref b3SharedMemoryCommandHandle__ commandHandle, double startPosX, double startPosY, double startPosZ) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///startOrnX: double + ///startOrnY: double + ///startOrnZ: double + ///startOrnW: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateBoxCommandSetStartOrientation")] +public static extern int b3CreateBoxCommandSetStartOrientation(ref b3SharedMemoryCommandHandle__ commandHandle, double startOrnX, double startOrnY, double startOrnZ, double startOrnW) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///halfExtentsX: double + ///halfExtentsY: double + ///halfExtentsZ: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateBoxCommandSetHalfExtents")] +public static extern int b3CreateBoxCommandSetHalfExtents(ref b3SharedMemoryCommandHandle__ commandHandle, double halfExtentsX, double halfExtentsY, double halfExtentsZ) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///mass: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateBoxCommandSetMass")] +public static extern int b3CreateBoxCommandSetMass(ref b3SharedMemoryCommandHandle__ commandHandle, double mass) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///collisionShapeType: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateBoxCommandSetCollisionShapeType")] +public static extern int b3CreateBoxCommandSetCollisionShapeType(ref b3SharedMemoryCommandHandle__ commandHandle, int collisionShapeType) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///red: double + ///green: double + ///blue: double + ///alpha: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateBoxCommandSetColorRGBA")] +public static extern int b3CreateBoxCommandSetColorRGBA(ref b3SharedMemoryCommandHandle__ commandHandle, double red, double green, double blue, double alpha) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///bodyIndex: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreatePoseCommandInit")] +public static extern System.IntPtr b3CreatePoseCommandInit(ref b3PhysicsClientHandle__ physClient, int bodyIndex) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///startPosX: double + ///startPosY: double + ///startPosZ: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreatePoseCommandSetBasePosition")] +public static extern int b3CreatePoseCommandSetBasePosition(ref b3SharedMemoryCommandHandle__ commandHandle, double startPosX, double startPosY, double startPosZ) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///startOrnX: double + ///startOrnY: double + ///startOrnZ: double + ///startOrnW: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreatePoseCommandSetBaseOrientation")] +public static extern int b3CreatePoseCommandSetBaseOrientation(ref b3SharedMemoryCommandHandle__ commandHandle, double startOrnX, double startOrnY, double startOrnZ, double startOrnW) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///linVel: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreatePoseCommandSetBaseLinearVelocity")] +public static extern int b3CreatePoseCommandSetBaseLinearVelocity(ref b3SharedMemoryCommandHandle__ commandHandle, ref double linVel) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///angVel: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreatePoseCommandSetBaseAngularVelocity")] +public static extern int b3CreatePoseCommandSetBaseAngularVelocity(ref b3SharedMemoryCommandHandle__ commandHandle, ref double angVel) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///numJointPositions: int + ///jointPositions: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreatePoseCommandSetJointPositions")] +public static extern int b3CreatePoseCommandSetJointPositions(ref b3SharedMemoryCommandHandle__ commandHandle, int numJointPositions, ref double jointPositions) ; + + + /// Return Type: int + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///jointIndex: int + ///jointPosition: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreatePoseCommandSetJointPosition")] +public static extern int b3CreatePoseCommandSetJointPosition(ref b3PhysicsClientHandle__ physClient, ref b3SharedMemoryCommandHandle__ commandHandle, int jointIndex, double jointPosition) ; + + + /// Return Type: int + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///numJointVelocities: int + ///jointVelocities: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreatePoseCommandSetJointVelocities")] +public static extern int b3CreatePoseCommandSetJointVelocities(ref b3PhysicsClientHandle__ physClient, ref b3SharedMemoryCommandHandle__ commandHandle, int numJointVelocities, ref double jointVelocities) ; + + + /// Return Type: int + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///jointIndex: int + ///jointVelocity: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreatePoseCommandSetJointVelocity")] +public static extern int b3CreatePoseCommandSetJointVelocity(ref b3PhysicsClientHandle__ physClient, ref b3SharedMemoryCommandHandle__ commandHandle, int jointIndex, double jointVelocity) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///bodyUniqueId: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateSensorCommandInit")] +public static extern System.IntPtr b3CreateSensorCommandInit(ref b3PhysicsClientHandle__ physClient, int bodyUniqueId) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///jointIndex: int + ///enable: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateSensorEnable6DofJointForceTorqueSensor")] +public static extern int b3CreateSensorEnable6DofJointForceTorqueSensor(ref b3SharedMemoryCommandHandle__ commandHandle, int jointIndex, int enable) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///linkIndex: int + ///enable: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateSensorEnableIMUForLink")] +public static extern int b3CreateSensorEnableIMUForLink(ref b3SharedMemoryCommandHandle__ commandHandle, int linkIndex, int enable) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///bodyUniqueId: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestActualStateCommandInit")] +public static extern System.IntPtr b3RequestActualStateCommandInit(ref b3PhysicsClientHandle__ physClient, int bodyUniqueId) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///computeLinkVelocity: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestActualStateCommandComputeLinkVelocity")] +public static extern int b3RequestActualStateCommandComputeLinkVelocity(ref b3SharedMemoryCommandHandle__ commandHandle, int computeLinkVelocity) ; + + + /// Return Type: int + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* + ///jointIndex: int + ///state: b3JointSensorState* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetJointState")] +public static extern int b3GetJointState(ref b3PhysicsClientHandle__ physClient, ref b3SharedMemoryStatusHandle__ statusHandle, int jointIndex, ref b3JointSensorState state) ; + + + /// Return Type: int + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* + ///linkIndex: int + ///state: b3LinkState* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetLinkState")] +public static extern int b3GetLinkState(ref b3PhysicsClientHandle__ physClient, ref b3SharedMemoryStatusHandle__ statusHandle, int linkIndex, ref b3LinkState state) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///rayFromWorldX: double + ///rayFromWorldY: double + ///rayFromWorldZ: double + ///rayToWorldX: double + ///rayToWorldY: double + ///rayToWorldZ: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3PickBody")] +public static extern System.IntPtr b3PickBody(ref b3PhysicsClientHandle__ physClient, double rayFromWorldX, double rayFromWorldY, double rayFromWorldZ, double rayToWorldX, double rayToWorldY, double rayToWorldZ) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///rayFromWorldX: double + ///rayFromWorldY: double + ///rayFromWorldZ: double + ///rayToWorldX: double + ///rayToWorldY: double + ///rayToWorldZ: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3MovePickedBody")] +public static extern System.IntPtr b3MovePickedBody(ref b3PhysicsClientHandle__ physClient, double rayFromWorldX, double rayFromWorldY, double rayFromWorldZ, double rayToWorldX, double rayToWorldY, double rayToWorldZ) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RemovePickingConstraint")] +public static extern System.IntPtr b3RemovePickingConstraint(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///rayFromWorldX: double + ///rayFromWorldY: double + ///rayFromWorldZ: double + ///rayToWorldX: double + ///rayToWorldY: double + ///rayToWorldZ: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateRaycastCommandInit")] +public static extern System.IntPtr b3CreateRaycastCommandInit(ref b3PhysicsClientHandle__ physClient, double rayFromWorldX, double rayFromWorldY, double rayFromWorldZ, double rayToWorldX, double rayToWorldY, double rayToWorldZ) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3CreateRaycastBatchCommandInit")] +public static extern System.IntPtr b3CreateRaycastBatchCommandInit(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///rayFromWorld: double* + ///rayToWorld: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RaycastBatchAddRay")] +public static extern void b3RaycastBatchAddRay(ref b3SharedMemoryCommandHandle__ commandHandle, ref double rayFromWorld, ref double rayToWorld) ; + + + /// Return Type: void + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///raycastInfo: b3RaycastInformation* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetRaycastInformation")] +public static extern void b3GetRaycastInformation(ref b3PhysicsClientHandle__ physClient, ref b3RaycastInformation raycastInfo) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ApplyExternalForceCommandInit")] +public static extern System.IntPtr b3ApplyExternalForceCommandInit(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///bodyUniqueId: int + ///linkId: int + ///force: double* + ///position: double* + ///flags: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ApplyExternalForce")] +public static extern void b3ApplyExternalForce(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueId, int linkId, ref double force, ref double position, int flags) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///bodyUniqueId: int + ///linkId: int + ///torque: double* + ///flags: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ApplyExternalTorque")] +public static extern void b3ApplyExternalTorque(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyUniqueId, int linkId, ref double torque, int flags) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadBunnyCommandInit")] +public static extern System.IntPtr b3LoadBunnyCommandInit(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///scale: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadBunnySetScale")] +public static extern int b3LoadBunnySetScale(ref b3SharedMemoryCommandHandle__ commandHandle, double scale) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///mass: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadBunnySetMass")] +public static extern int b3LoadBunnySetMass(ref b3SharedMemoryCommandHandle__ commandHandle, double mass) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///collisionMargin: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3LoadBunnySetCollisionMargin")] +public static extern int b3LoadBunnySetCollisionMargin(ref b3SharedMemoryCommandHandle__ commandHandle, double collisionMargin) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestVREventsCommandInit")] +public static extern System.IntPtr b3RequestVREventsCommandInit(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///deviceTypeFilter: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3VREventsSetDeviceTypeFilter")] +public static extern void b3VREventsSetDeviceTypeFilter(ref b3SharedMemoryCommandHandle__ commandHandle, int deviceTypeFilter) ; + + + /// Return Type: void + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///vrEventsData: b3VREventsData* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetVREventsData")] +public static extern void b3GetVREventsData(ref b3PhysicsClientHandle__ physClient, ref b3VREventsData vrEventsData) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetVRCameraStateCommandInit")] +public static extern System.IntPtr b3SetVRCameraStateCommandInit(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///rootPos: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetVRCameraRootPosition")] +public static extern int b3SetVRCameraRootPosition(ref b3SharedMemoryCommandHandle__ commandHandle, ref double rootPos) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///rootOrn: double* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetVRCameraRootOrientation")] +public static extern int b3SetVRCameraRootOrientation(ref b3SharedMemoryCommandHandle__ commandHandle, ref double rootOrn) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///objectUniqueId: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetVRCameraTrackingObject")] +public static extern int b3SetVRCameraTrackingObject(ref b3SharedMemoryCommandHandle__ commandHandle, int objectUniqueId) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///flag: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetVRCameraTrackingObjectFlag")] +public static extern int b3SetVRCameraTrackingObjectFlag(ref b3SharedMemoryCommandHandle__ commandHandle, int flag) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestKeyboardEventsCommandInit")] +public static extern System.IntPtr b3RequestKeyboardEventsCommandInit(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: void + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///keyboardEventsData: b3KeyboardEventsData* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetKeyboardEventsData")] +public static extern void b3GetKeyboardEventsData(ref b3PhysicsClientHandle__ physClient, ref b3KeyboardEventsData keyboardEventsData) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3RequestMouseEventsCommandInit")] +public static extern System.IntPtr b3RequestMouseEventsCommandInit(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: void + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///mouseEventsData: b3MouseEventsData* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetMouseEventsData")] +public static extern void b3GetMouseEventsData(ref b3PhysicsClientHandle__ physClient, ref b3MouseEventsData mouseEventsData) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3StateLoggingCommandInit")] +public static extern System.IntPtr b3StateLoggingCommandInit(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///loggingType: int + ///fileName: char* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3StateLoggingStart")] +public static extern int b3StateLoggingStart(ref b3SharedMemoryCommandHandle__ commandHandle, int loggingType, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///objectUniqueId: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3StateLoggingAddLoggingObjectUniqueId")] +public static extern int b3StateLoggingAddLoggingObjectUniqueId(ref b3SharedMemoryCommandHandle__ commandHandle, int objectUniqueId) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///maxLogDof: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3StateLoggingSetMaxLogDof")] +public static extern int b3StateLoggingSetMaxLogDof(ref b3SharedMemoryCommandHandle__ commandHandle, int maxLogDof) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///linkIndexA: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3StateLoggingSetLinkIndexA")] +public static extern int b3StateLoggingSetLinkIndexA(ref b3SharedMemoryCommandHandle__ commandHandle, int linkIndexA) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///linkIndexB: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3StateLoggingSetLinkIndexB")] +public static extern int b3StateLoggingSetLinkIndexB(ref b3SharedMemoryCommandHandle__ commandHandle, int linkIndexB) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///bodyAUniqueId: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3StateLoggingSetBodyAUniqueId")] +public static extern int b3StateLoggingSetBodyAUniqueId(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyAUniqueId) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///bodyBUniqueId: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3StateLoggingSetBodyBUniqueId")] +public static extern int b3StateLoggingSetBodyBUniqueId(ref b3SharedMemoryCommandHandle__ commandHandle, int bodyBUniqueId) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///deviceTypeFilter: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3StateLoggingSetDeviceTypeFilter")] +public static extern int b3StateLoggingSetDeviceTypeFilter(ref b3SharedMemoryCommandHandle__ commandHandle, int deviceTypeFilter) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///logFlags: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3StateLoggingSetLogFlags")] +public static extern int b3StateLoggingSetLogFlags(ref b3SharedMemoryCommandHandle__ commandHandle, int logFlags) ; + + + /// Return Type: int + ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetStatusLoggingUniqueId")] +public static extern int b3GetStatusLoggingUniqueId(ref b3SharedMemoryStatusHandle__ statusHandle) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///loggingUniqueId: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3StateLoggingStop")] +public static extern int b3StateLoggingStop(ref b3SharedMemoryCommandHandle__ commandHandle, int loggingUniqueId) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///name: char* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3ProfileTimingCommandInit")] +public static extern System.IntPtr b3ProfileTimingCommandInit(ref b3PhysicsClientHandle__ physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string name) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///duration: int + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetProfileTimingDuractionInMicroSeconds")] +public static extern void b3SetProfileTimingDuractionInMicroSeconds(ref b3SharedMemoryCommandHandle__ commandHandle, int duration) ; + + + /// Return Type: void + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///timeOutInSeconds: double + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetTimeOut")] +public static extern void b3SetTimeOut(ref b3PhysicsClientHandle__ physClient, double timeOutInSeconds) ; + + + /// Return Type: double + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3GetTimeOut")] +public static extern double b3GetTimeOut(ref b3PhysicsClientHandle__ physClient) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + ///path: char* + [System.Runtime.InteropServices.DllImportAttribute("", EntryPoint="b3SetAdditionalSearchPath")] +public static extern System.IntPtr b3SetAdditionalSearchPath(ref b3PhysicsClientHandle__ physClient, System.IntPtr path) ; + + + /// Return Type: void + ///posA: double* + ///ornA: double* + ///posB: double* + ///ornB: double* + ///outPos: double* + ///outOrn: double* + [System.Runtime.InteropServices.DllImportAttribute("", 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) ; + + + /// Return Type: void + ///pos: double* + ///orn: double* + ///outPos: double* + ///outOrn: double* + [System.Runtime.InteropServices.DllImportAttribute("", 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 new file mode 100644 index 000000000..026e7a709 --- /dev/null +++ b/examples/pybullet/unity3d/examples/NewBehaviourScript.cs @@ -0,0 +1,86 @@ +using System.Collections; +using System.Collections.Generic; +using UnityEngine; +using UnityEngine.UI; +using System.Runtime.InteropServices; +using System; + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] + + +public class NewBehaviourScript : MonoBehaviour { + + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint = "b3ConnectSharedMemory")] + public static extern System.IntPtr b3ConnectSharedMemory(int key); + + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint = "b3CreateInProcessPhysicsServerAndConnect")] + public static extern System.IntPtr b3CreateInProcessPhysicsServerAndConnect(int argc, ref System.IntPtr argv); + + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint = "b3InitStepSimulationCommand")] + public static extern System.IntPtr b3InitStepSimulationCommand(IntPtr physClient); + + + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", 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); + + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint = "b3InitResetSimulationCommand")] + public static extern System.IntPtr b3InitResetSimulationCommand(IntPtr physClient); + + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint = "b3SubmitClientCommandAndWaitStatus")] + public static extern System.IntPtr b3SubmitClientCommandAndWaitStatus(IntPtr physClient, IntPtr commandHandle); + + + [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; + + // Use this for initialization + void Start () { + text = GetComponent(); + CallMe(IWasCalled); + sharedAPI = CreateSharedAPI(30); + + IntPtr pybullet = b3ConnectSharedMemory(12347); + IntPtr cmd = b3InitResetSimulationCommand(pybullet); + IntPtr status = b3SubmitClientCommandAndWaitStatus(pybullet, cmd); + cmd = b3LoadUrdfCommandInit(pybullet, "plane.urdf"); + status = b3SubmitClientCommandAndWaitStatus(pybullet, cmd); + //IntPtr clientPtr = b3CreateInProcessPhysicsServerAndConnect(0, ref ptr); + } + + // Update is called once per frame + void Update () { + IntPtr cmd = b3InitStepSimulationCommand(pybullet); + IntPtr status = b3SubmitClientCommandAndWaitStatus(pybullet, cmd); + + //System.IO.Directory.GetCurrentDirectory().ToString();// + //text.text = Add(4, 5).ToString(); + text.text = UnityEngine.Random.Range(0f, 1f).ToString();// GetMyIdPlusTen(sharedAPI).ToString(); + } + + void OnDestroy() + { + + DeleteSharedAPI(sharedAPI); + } +} diff --git a/examples/pybullet/unity3d/examples/NewBehaviourScript.cs.meta b/examples/pybullet/unity3d/examples/NewBehaviourScript.cs.meta new file mode 100644 index 000000000..6e595b031 --- /dev/null +++ b/examples/pybullet/unity3d/examples/NewBehaviourScript.cs.meta @@ -0,0 +1,12 @@ +fileFormatVersion: 2 +guid: 6197b3a0389e92c47b7d8698e5f61f06 +timeCreated: 1505961790 +licenseType: Free +MonoImporter: + serializedVersion: 2 + defaultReferences: [] + executionOrder: 0 + icon: {instanceID: 0} + userData: + assetBundleName: + assetBundleVariant: diff --git a/examples/pybullet/unity3d/readme.txt b/examples/pybullet/unity3d/readme.txt new file mode 100644 index 000000000..43497b816 --- /dev/null +++ b/examples/pybullet/unity3d/readme.txt @@ -0,0 +1,33 @@ +Quick prototype to connect Unity 3D to pybullet + +Generate C# Native Methods using the Microsoft PInvoke Signature Toolkit: + +sigimp.exe /lang:cs e:\develop\bullet3\examples\SharedMemory\PhysicsClientC_API.h + +Add some #define B3_SHARED_API __declspec(dllexport) to the exported methods, +replace [3], [4], [16] by [] to get sigimp.exe working. + +This generates autogen/NativeMethods.cs + +Then put pybullet.dll in the right location, so Unity finds it. + +NewBehaviourScript.cs is a 1 evening prototype that works within Unity 3D: +Create a connection to pybullet, reset the world, load a urdf at startup. +Step the simulation each Update. + +Now the real work can start, converting Unity objects to pybullet, +pybullet robots to Unity, synchronizing the transforms each Update. + +void Start () { + IntPtr pybullet = b3ConnectSharedMemory(12347); + IntPtr cmd = b3InitResetSimulationCommand(pybullet); + IntPtr status = b3SubmitClientCommandAndWaitStatus(pybullet, cmd); + cmd = b3LoadUrdfCommandInit(pybullet, "plane.urdf"); + status = b3SubmitClientCommandAndWaitStatus(pybullet, cmd); +} + +void Update () +{ + IntPtr cmd = b3InitStepSimulationCommand(pybullet); + IntPtr status = b3SubmitClientCommandAndWaitStatus(pybullet, cmd); +}