mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-13 21:30:09 +00:00
Quick first prototype/test to integrate pybullet into Unity,
see readme.txt for details.
This commit is contained in:
parent
ae8f12e8ba
commit
6a7efac4c3
@ -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);
|
||||
@ -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);
|
||||
@ -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);
|
||||
@ -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);
|
||||
@ -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;
|
||||
|
@ -10,6 +10,10 @@ B3_DECLARE_HANDLE(b3PhysicsClientHandle);
|
||||
B3_DECLARE_HANDLE(b3SharedMemoryCommandHandle);
|
||||
B3_DECLARE_HANDLE(b3SharedMemoryStatusHandle);
|
||||
|
||||
#ifdef _WIN32
|
||||
#define B3_SHARED_API __declspec(dllexport)
|
||||
#endif
|
||||
|
||||
|
||||
///There are several connection methods, see following header files:
|
||||
#include "PhysicsClientSharedMemory_C_API.h"
|
||||
@ -39,7 +43,7 @@ void b3DisconnectSharedMemory(b3PhysicsClientHandle physClient);
|
||||
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
|
||||
@ -67,7 +71,7 @@ int b3GetStatusActualState(b3SharedMemoryStatusHandle statusHandle,
|
||||
|
||||
|
||||
b3SharedMemoryCommandHandle b3RequestCollisionInfoCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId);
|
||||
int b3GetStatusAABB(b3SharedMemoryStatusHandle statusHandle, int linkIndex, double aabbMin[3], double aabbMax[3]);
|
||||
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);
|
||||
@ -111,8 +115,8 @@ 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 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);
|
||||
@ -135,18 +139,18 @@ void b3GetDebugLines(b3PhysicsClientHandle physClient, struct b3DebugLines* l
|
||||
///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]);
|
||||
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);
|
||||
|
||||
|
||||
/// 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);
|
||||
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);
|
||||
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]);
|
||||
void b3UserDebugTextSetOrientation(b3SharedMemoryCommandHandle commandHandle, double orientation[/*4*/]);
|
||||
|
||||
void b3UserDebugItemSetParentObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex);
|
||||
|
||||
@ -158,7 +162,7 @@ b3SharedMemoryCommandHandle b3InitUserDebugDrawRemove(b3PhysicsClientHandle phys
|
||||
b3SharedMemoryCommandHandle b3InitUserDebugDrawRemoveAll(b3PhysicsClientHandle physClient);
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitDebugDrawingCommand(b3PhysicsClientHandle physClient);
|
||||
void b3SetDebugObjectColor(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex, double objectColorRGB[3]);
|
||||
void b3SetDebugObjectColor(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex, double objectColorRGB[/*3*/]);
|
||||
void b3RemoveDebugObjectColor(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex);
|
||||
|
||||
///All debug items unique Ids are positive: a negative unique Id means failure.
|
||||
@ -167,10 +171,10 @@ 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 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 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);
|
||||
@ -180,19 +184,19 @@ void b3RequestCameraImageSelectRenderer(b3SharedMemoryCommandHandle commandHandl
|
||||
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]);
|
||||
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*/]);
|
||||
|
||||
///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]);
|
||||
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*/]);
|
||||
|
||||
|
||||
/* obsolete, please use b3ComputeViewProjectionMatrices */
|
||||
void b3RequestCameraImageSetViewMatrix(b3SharedMemoryCommandHandle command, const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3]);
|
||||
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);
|
||||
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);
|
||||
/* obsolete, please use b3ComputeViewProjectionMatrices */
|
||||
@ -217,7 +221,7 @@ void b3SetClosestDistanceThreshold(b3SharedMemoryCommandHandle commandHandle, do
|
||||
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]);
|
||||
b3SharedMemoryCommandHandle b3InitAABBOverlapQuery(b3PhysicsClientHandle physClient, const double aabbMin[/*3*/],const double aabbMax[/*3*/]);
|
||||
void b3GetAABBOverlapResults(b3PhysicsClientHandle physClient, struct b3AABBOverlapData* data);
|
||||
|
||||
//request visual shape information
|
||||
@ -230,8 +234,8 @@ int b3GetStatusTextureUniqueId(b3SharedMemoryStatusHandle statusHandle);
|
||||
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]);
|
||||
void b3UpdateVisualShapeRGBAColor(b3SharedMemoryCommandHandle commandHandle, double rgbaColor[/*4*/]);
|
||||
void b3UpdateVisualShapeSpecularColor(b3SharedMemoryCommandHandle commandHandle, double specularColor[/*3*/]);
|
||||
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient);
|
||||
@ -262,20 +266,20 @@ int b3PhysicsParamSetRestitutionVelocityThreshold(b3SharedMemoryCommandHandle co
|
||||
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);
|
||||
|
||||
|
||||
|
||||
@ -300,10 +304,10 @@ 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);
|
||||
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 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,
|
||||
int* bodyUniqueId,
|
||||
@ -345,14 +349,14 @@ int b3JointControlSetDesiredForceTorque(b3SharedMemoryCommandHandle commandHandl
|
||||
|
||||
b3SharedMemoryCommandHandle b3CreateCollisionShapeCommandInit(b3PhysicsClientHandle physClient);
|
||||
int b3CreateCollisionShapeAddSphere(b3SharedMemoryCommandHandle commandHandle,double radius);
|
||||
int b3CreateCollisionShapeAddBox(b3SharedMemoryCommandHandle commandHandle,double halfExtents[3]);
|
||||
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]);
|
||||
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);
|
||||
|
||||
void b3CreateCollisionShapeSetChildTransform(b3SharedMemoryCommandHandle commandHandle,int shapeIndex, double childPosition[3], double childOrientation[4]);
|
||||
void b3CreateCollisionShapeSetChildTransform(b3SharedMemoryCommandHandle commandHandle,int shapeIndex, double childPosition[/*3*/], double childOrientation[/*4*/]);
|
||||
|
||||
int b3GetStatusCollisionShapeUniqueId(b3SharedMemoryStatusHandle statusHandle);
|
||||
|
||||
@ -360,17 +364,17 @@ b3SharedMemoryCommandHandle b3CreateVisualShapeCommandInit(b3PhysicsClientHandle
|
||||
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]);
|
||||
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,
|
||||
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
|
||||
@ -397,8 +401,8 @@ int b3CreateBoxCommandSetColorRGBA(b3SharedMemoryCommandHandle commandHandle, do
|
||||
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]);
|
||||
int b3CreatePoseCommandSetBaseLinearVelocity(b3SharedMemoryCommandHandle commandHandle, double linVel[/*3*/]);
|
||||
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);
|
||||
@ -434,7 +438,7 @@ b3SharedMemoryCommandHandle b3CreateRaycastCommandInit(b3PhysicsClientHandle phy
|
||||
double rayToWorldX, double rayToWorldY, double rayToWorldZ);
|
||||
|
||||
b3SharedMemoryCommandHandle b3CreateRaycastBatchCommandInit(b3PhysicsClientHandle physClient);
|
||||
void b3RaycastBatchAddRay(b3SharedMemoryCommandHandle commandHandle, const double rayFromWorld[3], const double rayToWorld[3]);
|
||||
void b3RaycastBatchAddRay(b3SharedMemoryCommandHandle commandHandle, const double rayFromWorld[/*3*/], const double rayToWorld[/*3*/]);
|
||||
|
||||
void b3GetRaycastInformation(b3PhysicsClientHandle physClient, struct b3RaycastInformation* raycastInfo);
|
||||
|
||||
@ -442,8 +446,8 @@ void b3GetRaycastInformation(b3PhysicsClientHandle physClient, struct b3RaycastI
|
||||
|
||||
/// 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);
|
||||
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);
|
||||
|
||||
///experiments of robots interacting with non-rigid objects (such as btSoftBody)
|
||||
b3SharedMemoryCommandHandle b3LoadBunnyCommandInit(b3PhysicsClientHandle physClient);
|
||||
@ -458,8 +462,8 @@ void b3VREventsSetDeviceTypeFilter(b3SharedMemoryCommandHandle commandHandle, in
|
||||
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 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);
|
||||
|
||||
@ -493,8 +497,8 @@ double b3GetTimeOut(b3PhysicsClientHandle physClient);
|
||||
|
||||
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]);
|
||||
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*/]);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
|
@ -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);
|
||||
|
@ -7,7 +7,7 @@
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
b3PhysicsClientHandle b3ConnectSharedMemory(int key);
|
||||
B3_SHARED_API b3PhysicsClientHandle b3ConnectSharedMemory(int key);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
|
@ -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);
|
||||
|
@ -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);
|
||||
|
3113
examples/pybullet/unity3d/autogen/NativeMethods.cs
Normal file
3113
examples/pybullet/unity3d/autogen/NativeMethods.cs
Normal file
File diff suppressed because it is too large
Load Diff
86
examples/pybullet/unity3d/examples/NewBehaviourScript.cs
Normal file
86
examples/pybullet/unity3d/examples/NewBehaviourScript.cs
Normal file
@ -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<int> 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<Text>();
|
||||
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);
|
||||
}
|
||||
}
|
@ -0,0 +1,12 @@
|
||||
fileFormatVersion: 2
|
||||
guid: 6197b3a0389e92c47b7d8698e5f61f06
|
||||
timeCreated: 1505961790
|
||||
licenseType: Free
|
||||
MonoImporter:
|
||||
serializedVersion: 2
|
||||
defaultReferences: []
|
||||
executionOrder: 0
|
||||
icon: {instanceID: 0}
|
||||
userData:
|
||||
assetBundleName:
|
||||
assetBundleVariant:
|
33
examples/pybullet/unity3d/readme.txt
Normal file
33
examples/pybullet/unity3d/readme.txt
Normal file
@ -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);
|
||||
}
|
Loading…
Reference in New Issue
Block a user