2015-07-23 01:06:05 +00:00
# ifndef PHYSICS_CLIENT_C_API_H
# define PHYSICS_CLIENT_C_API_H
2015-09-17 06:09:10 +00:00
//#include "SharedMemoryBlock.h"
# include "SharedMemoryPublic.h"
2015-07-23 01:06:05 +00:00
# define B3_DECLARE_HANDLE(name) typedef struct name##__ { int unused; } *name
B3_DECLARE_HANDLE ( b3PhysicsClientHandle ) ;
2015-09-17 06:09:10 +00:00
B3_DECLARE_HANDLE ( b3SharedMemoryCommandHandle ) ;
B3_DECLARE_HANDLE ( b3SharedMemoryStatusHandle ) ;
2017-09-21 06:18:18 +00:00
# ifdef _WIN32
2017-09-21 15:37:00 +00:00
# define B3_SHARED_API __declspec(dllexport)
# elif defined (__GNUC__)
# define B3_SHARED_API __attribute__((visibility("default")))
# else
# define B3_SHARED_API
2017-09-21 06:18:18 +00:00
# endif
2015-07-23 01:06:05 +00:00
2016-11-04 20:15:10 +00:00
///There are several connection methods, see following header files:
# include "PhysicsClientSharedMemory_C_API.h"
# include "PhysicsClientSharedMemory2_C_API.h"
# include "PhysicsDirectC_API.h"
2017-09-06 20:18:39 +00:00
# ifdef BT_ENABLE_ENET
2016-11-04 20:15:10 +00:00
# include "PhysicsClientUDP_C_API.h"
2017-09-06 20:18:39 +00:00
# endif
# ifdef BT_ENABLE_CLSOCKET
# include "PhysicsClientTCP_C_API.h"
# endif
2016-11-04 20:15:10 +00:00
# include "SharedMemoryInProcessPhysicsC_API.h"
2015-07-23 01:06:05 +00:00
# ifdef __cplusplus
extern " C " {
# endif
2016-11-04 20:15:10 +00:00
2015-07-23 01:06:05 +00:00
2016-04-13 20:06:15 +00:00
///b3DisconnectSharedMemory will disconnect the client from the server and cleanup memory.
2017-09-21 23:40:19 +00:00
B3_SHARED_API void b3DisconnectSharedMemory ( b3PhysicsClientHandle physClient ) ;
2015-07-23 01:06:05 +00:00
2016-04-13 20:06:15 +00:00
///There can only be 1 outstanding command. Check if a command can be send.
2017-09-21 23:40:19 +00:00
B3_SHARED_API int b3CanSubmitCommand ( b3PhysicsClientHandle physClient ) ;
2015-07-23 01:06:05 +00:00
2016-04-13 20:06:15 +00:00
///blocking submit command and wait for status
2017-09-21 06:18:18 +00:00
B3_SHARED_API b3SharedMemoryStatusHandle b3SubmitClientCommandAndWaitStatus ( b3PhysicsClientHandle physClient , b3SharedMemoryCommandHandle commandHandle ) ;
2015-09-17 16:37:44 +00:00
2016-04-13 20:06:15 +00:00
///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'.
2017-09-21 23:40:19 +00:00
B3_SHARED_API int b3SubmitClientCommand ( b3PhysicsClientHandle physClient , b3SharedMemoryCommandHandle commandHandle ) ;
2015-07-23 01:06:05 +00:00
2015-09-17 16:37:44 +00:00
///non-blocking check status
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryStatusHandle b3ProcessServerStatus ( b3PhysicsClientHandle physClient ) ;
2015-09-17 16:37:44 +00:00
2016-04-13 20:06:15 +00:00
/// Get the physics server return status type. See EnumSharedMemoryServerStatus in SharedMemoryPublic.h for error codes.
2017-09-21 23:40:19 +00:00
B3_SHARED_API int b3GetStatusType ( b3SharedMemoryStatusHandle statusHandle ) ;
2015-09-17 16:37:44 +00:00
2017-09-23 02:17:57 +00:00
///Plugin system, load and unload a plugin, execute a command
B3_SHARED_API b3SharedMemoryCommandHandle b3CreateCustomCommand ( b3PhysicsClientHandle physClient ) ;
B3_SHARED_API void b3CustomCommandLoadPlugin ( b3SharedMemoryCommandHandle commandHandle , const char * pluginPath , int options ) ;
B3_SHARED_API int b3GetStatusPluginUniqueId ( b3SharedMemoryStatusHandle statusHandle ) ;
B3_SHARED_API int b3GetStatusPluginCommandResult ( b3SharedMemoryStatusHandle statusHandle ) ;
B3_SHARED_API void b3CustomCommandUnloadPlugin ( b3SharedMemoryCommandHandle commandHandle , int pluginUniqueId ) ;
B3_SHARED_API void b3CustomCommandExecutePluginCommand ( b3SharedMemoryCommandHandle commandHandle , int pluginUniqueId , int commandUniqueId , const char * arguments ) ;
2017-09-21 23:40:19 +00:00
B3_SHARED_API int b3GetStatusBodyIndices ( b3SharedMemoryStatusHandle statusHandle , int * bodyIndicesOut , int bodyIndicesCapacity ) ;
2016-06-13 17:11:28 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API int b3GetStatusBodyIndex ( b3SharedMemoryStatusHandle statusHandle ) ;
2015-10-13 18:32:25 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API int b3GetStatusActualState ( b3SharedMemoryStatusHandle statusHandle ,
2015-11-05 00:08:28 +00:00
int * bodyUniqueId ,
int * numDegreeOfFreedomQ ,
int * numDegreeOfFreedomU ,
const double * rootLocalInertialFrame [ ] ,
const double * actualStateQ [ ] ,
const double * actualStateQdot [ ] ,
const double * jointReactionForces [ ] ) ;
2017-06-17 01:10:10 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3RequestCollisionInfoCommandInit ( b3PhysicsClientHandle physClient , int bodyUniqueId ) ;
B3_SHARED_API int b3GetStatusAABB ( b3SharedMemoryStatusHandle statusHandle , int linkIndex , double aabbMin [ /*3*/ ] , double aabbMax [ /*3*/ ] ) ;
2017-06-16 02:46:27 +00:00
2017-01-23 03:08:31 +00:00
///If you re-connected to an existing server, or server changed otherwise, sync the body info and user constraints etc.
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3InitSyncBodyInfoCommand ( b3PhysicsClientHandle physClient ) ;
2017-01-21 02:13:24 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3InitRemoveBodyCommand ( b3PhysicsClientHandle physClient , int bodyUniqueId ) ;
2017-05-04 04:53:29 +00:00
2016-09-27 19:13:45 +00:00
///return the total number of bodies in the simulation
2017-09-21 23:40:19 +00:00
B3_SHARED_API int b3GetNumBodies ( b3PhysicsClientHandle physClient ) ;
2016-09-27 19:13:45 +00:00
/// return the body unique id, given the index in range [0 , b3GetNumBodies() )
2017-09-21 23:40:19 +00:00
B3_SHARED_API int b3GetBodyUniqueId ( b3PhysicsClientHandle physClient , int serialIndex ) ;
2016-09-27 19:13:45 +00:00
///given a body unique id, return the body information. See b3BodyInfo in SharedMemoryPublic.h
2017-09-21 23:40:19 +00:00
B3_SHARED_API int b3GetBodyInfo ( b3PhysicsClientHandle physClient , int bodyUniqueId , struct b3BodyInfo * info ) ;
2016-09-27 19:13:45 +00:00
2016-04-13 20:06:15 +00:00
///give a unique body index (after loading the body) return the number of joints.
2017-09-21 23:40:19 +00:00
B3_SHARED_API int b3GetNumJoints ( b3PhysicsClientHandle physClient , int bodyIndex ) ;
2015-07-23 01:06:05 +00:00
2016-07-20 18:01:02 +00:00
///given a body and joint index, return the joint information. See b3JointInfo in SharedMemoryPublic.h
2017-09-21 23:40:19 +00:00
B3_SHARED_API int b3GetJointInfo ( b3PhysicsClientHandle physClient , int bodyIndex , int jointIndex , struct b3JointInfo * info ) ;
2017-05-02 05:18:54 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3GetDynamicsInfoCommandInit ( b3PhysicsClientHandle physClient , int bodyUniqueId , int linkIndex ) ;
2017-05-09 17:44:33 +00:00
///given a body unique id and link index, return the dynamics information. See b3DynamicsInfo in SharedMemoryPublic.h
2017-09-21 23:40:19 +00:00
B3_SHARED_API int b3GetDynamicsInfo ( b3SharedMemoryStatusHandle statusHandle , struct b3DynamicsInfo * info ) ;
2017-05-02 05:18:54 +00:00
2017-09-21 23:40:19 +00:00
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 ) ;
B3_SHARED_API b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand ( b3PhysicsClientHandle physClient , int parentBodyIndex , int parentJointIndex , int childBodyIndex , int childJointIndex , struct b3JointInfo * info ) ;
2017-01-23 03:08:31 +00:00
///return a unique id for the user constraint, after successful creation, or -1 for an invalid constraint id
2017-09-21 23:40:19 +00:00
B3_SHARED_API int b3GetStatusUserConstraintUniqueId ( b3SharedMemoryStatusHandle statusHandle ) ;
2017-01-23 03:08:31 +00:00
///change parameters of an existing user constraint
2017-09-21 23:40:19 +00:00
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 ) ;
2017-06-07 20:44:34 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3InitRemoveUserConstraintCommand ( b3PhysicsClientHandle physClient , int userConstraintUniqueId ) ;
2015-07-23 01:06:05 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API int b3GetNumUserConstraints ( b3PhysicsClientHandle physClient ) ;
B3_SHARED_API int b3GetUserConstraintInfo ( b3PhysicsClientHandle physClient , int constraintUniqueId , struct b3UserConstraint * info ) ;
2017-05-04 01:25:25 +00:00
/// return the user constraint id, given the index in range [0 , b3GetNumUserConstraints() )
2017-09-21 23:40:19 +00:00
B3_SHARED_API int b3GetUserConstraintId ( b3PhysicsClientHandle physClient , int serialIndex ) ;
2017-01-23 03:08:31 +00:00
2016-11-14 15:39:34 +00:00
///Request physics debug lines for debug visualization. The flags in debugMode are the same as used in Bullet
2016-04-13 20:06:15 +00:00
///See btIDebugDraw::DebugDrawModes in Bullet/src/LinearMath/btIDebugDraw.h
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestDebugLinesCommand ( b3PhysicsClientHandle physClient , int debugMode ) ;
2016-04-13 20:06:15 +00:00
2016-11-14 15:39:34 +00:00
///Get the pointers to the physics debug line information, after b3InitRequestDebugLinesCommand returns
2016-04-13 20:06:15 +00:00
///status CMD_DEBUG_LINES_COMPLETED
2017-09-21 23:40:19 +00:00
B3_SHARED_API void b3GetDebugLines ( b3PhysicsClientHandle physClient , struct b3DebugLines * lines ) ;
2017-02-22 01:36:54 +00:00
///configure the 3D OpenGL debug visualizer (enable/disable GUI widgets, shadows, position camera etc)
2017-09-21 23:40:19 +00:00
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*/ ] ) ;
2016-05-18 06:57:19 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestOpenGLVisualizerCameraCommand ( b3PhysicsClientHandle physClient ) ;
B3_SHARED_API int b3GetStatusOpenGLVisualizerCamera ( b3SharedMemoryStatusHandle statusHandle , struct b3OpenGLVisualizerCameraInfo * camera ) ;
2017-04-10 18:03:41 +00:00
2017-02-22 01:36:54 +00:00
2016-11-14 15:39:34 +00:00
/// Add/remove user-specific debug lines and debug text messages
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawAddLine3D ( b3PhysicsClientHandle physClient , double fromXYZ [ /*3*/ ] , double toXYZ [ /*3*/ ] , double colorRGB [ /*3*/ ] , double lineWidth , double lifeTime ) ;
Improve debug text/line rendering, can be use to draw frames and text in local coordinate of an object / link.
example:
kuka = p.loadURDF("kuka_iiwa/model.urdf")
p.getNumJoints(kuka)
pybullet.addUserDebugLine([0,0,0],[0,0,0.1],[0,0,1],trackObjectUniqueId=2,trackLinkIndex=6)
pybullet.addUserDebugText("tip", [0,0,0.1],textColorRGB=[1,0,0],trackObjectUniqueId=2,trackLinkIndex=6)
Also allow to render text using a given orientation (instead of pointing to the camera), example:
pybullet.addUserDebugText("tip", [0,0,0.1],textColorRGB=[1,0,0],textOrientation=[0,0,0,1], trackObjectUniqueId=2,trackLinkIndex=6)
Add drawTexturedTriangleMesh, for drawing 3d text.
Expose readSingleInstanceTransformToCPU, to extract position/orientation from graphics index.
updateTexture: allow to not flip texels around up axis
2017-05-24 05:05:26 +00:00
2017-09-21 23:40:19 +00:00
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*/ ] ) ;
Improve debug text/line rendering, can be use to draw frames and text in local coordinate of an object / link.
example:
kuka = p.loadURDF("kuka_iiwa/model.urdf")
p.getNumJoints(kuka)
pybullet.addUserDebugLine([0,0,0],[0,0,0.1],[0,0,1],trackObjectUniqueId=2,trackLinkIndex=6)
pybullet.addUserDebugText("tip", [0,0,0.1],textColorRGB=[1,0,0],trackObjectUniqueId=2,trackLinkIndex=6)
Also allow to render text using a given orientation (instead of pointing to the camera), example:
pybullet.addUserDebugText("tip", [0,0,0.1],textColorRGB=[1,0,0],textOrientation=[0,0,0,1], trackObjectUniqueId=2,trackLinkIndex=6)
Add drawTexturedTriangleMesh, for drawing 3d text.
Expose readSingleInstanceTransformToCPU, to extract position/orientation from graphics index.
updateTexture: allow to not flip texels around up axis
2017-05-24 05:05:26 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API void b3UserDebugItemSetParentObject ( b3SharedMemoryCommandHandle commandHandle , int objectUniqueId , int linkIndex ) ;
Improve debug text/line rendering, can be use to draw frames and text in local coordinate of an object / link.
example:
kuka = p.loadURDF("kuka_iiwa/model.urdf")
p.getNumJoints(kuka)
pybullet.addUserDebugLine([0,0,0],[0,0,0.1],[0,0,1],trackObjectUniqueId=2,trackLinkIndex=6)
pybullet.addUserDebugText("tip", [0,0,0.1],textColorRGB=[1,0,0],trackObjectUniqueId=2,trackLinkIndex=6)
Also allow to render text using a given orientation (instead of pointing to the camera), example:
pybullet.addUserDebugText("tip", [0,0,0.1],textColorRGB=[1,0,0],textOrientation=[0,0,0,1], trackObjectUniqueId=2,trackLinkIndex=6)
Add drawTexturedTriangleMesh, for drawing 3d text.
Expose readSingleInstanceTransformToCPU, to extract position/orientation from graphics index.
updateTexture: allow to not flip texels around up axis
2017-05-24 05:05:26 +00:00
2017-09-21 23:40:19 +00:00
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 ) ;
2017-01-17 23:42:32 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawRemove ( b3PhysicsClientHandle physClient , int debugItemUniqueId ) ;
B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawRemoveAll ( b3PhysicsClientHandle physClient ) ;
2016-11-21 15:42:11 +00:00
2017-09-21 23:40:19 +00:00
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 ) ;
2016-11-21 15:42:11 +00:00
2016-11-14 15:39:34 +00:00
///All debug items unique Ids are positive: a negative unique Id means failure.
2017-09-21 23:40:19 +00:00
B3_SHARED_API int b3GetDebugItemUniqueId ( b3SharedMemoryStatusHandle statusHandle ) ;
2016-11-14 15:39:34 +00:00
2016-11-21 15:42:11 +00:00
2016-05-18 06:57:19 +00:00
///request an image from a simulated camera, using a software renderer.
2017-09-21 23:40:19 +00:00
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 ) ;
2016-11-17 23:15:52 +00:00
///compute a view matrix, helper function for b3RequestCameraImageSetCameraMatrices
2017-09-21 23:40:19 +00:00
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*/ ] ) ;
2016-11-17 23:15:52 +00:00
///compute a projection matrix, helper function for b3RequestCameraImageSetCameraMatrices
2017-09-21 23:40:19 +00:00
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*/ ] ) ;
2016-11-17 23:15:52 +00:00
/* obsolete, please use b3ComputeViewProjectionMatrices */
2017-09-21 23:40:19 +00:00
B3_SHARED_API void b3RequestCameraImageSetViewMatrix ( b3SharedMemoryCommandHandle command , const float cameraPosition [ /*3*/ ] , const float cameraTargetPosition [ /*3*/ ] , const float cameraUp [ /*3*/ ] ) ;
2016-11-17 23:15:52 +00:00
/* obsolete, please use b3ComputeViewProjectionMatrices */
2017-09-21 23:40:19 +00:00
B3_SHARED_API void b3RequestCameraImageSetViewMatrix2 ( b3SharedMemoryCommandHandle commandHandle , const float cameraTargetPosition [ /*3*/ ] , float distance , float yaw , float pitch , float roll , int upAxis ) ;
2016-11-17 23:15:52 +00:00
/* obsolete, please use b3ComputeViewProjectionMatrices */
2017-09-21 23:40:19 +00:00
B3_SHARED_API void b3RequestCameraImageSetProjectionMatrix ( b3SharedMemoryCommandHandle command , float left , float right , float bottom , float top , float nearVal , float farVal ) ;
2016-11-17 23:15:52 +00:00
/* obsolete, please use b3ComputeViewProjectionMatrices */
2017-09-21 23:40:19 +00:00
B3_SHARED_API void b3RequestCameraImageSetFOVProjectionMatrix ( b3SharedMemoryCommandHandle command , float fov , float aspect , float nearVal , float farVal ) ;
2016-11-17 23:15:52 +00:00
2016-05-18 06:57:19 +00:00
2016-09-01 20:30:07 +00:00
///request an contact point information
2017-09-21 23:40:19 +00:00
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 ) ;
2016-10-19 05:05:28 +00:00
2016-11-10 05:01:04 +00:00
///compute the closest points between two bodies
2017-09-21 23:40:19 +00:00
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 ) ;
2016-11-10 05:01:04 +00:00
///get all the bodies that touch a given axis aligned bounding box specified in world space (min and max coordinates)
2017-09-21 23:40:19 +00:00
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 ) ;
2016-11-10 05:01:04 +00:00
2016-10-19 05:05:28 +00:00
//request visual shape information
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestVisualShapeInformation ( b3PhysicsClientHandle physClient , int bodyUniqueIdA ) ;
B3_SHARED_API void b3GetVisualShapeInformation ( b3PhysicsClientHandle physClient , struct b3VisualShapeInformation * visualShapeInfo ) ;
2016-10-19 05:05:28 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3InitLoadTexture ( b3PhysicsClientHandle physClient , const char * filename ) ;
B3_SHARED_API int b3GetStatusTextureUniqueId ( b3SharedMemoryStatusHandle statusHandle ) ;
2017-06-30 20:35:07 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3CreateChangeTextureCommandInit ( b3PhysicsClientHandle physClient , int textureUniqueId , int width , int height , const char * rgbPixels ) ;
2017-06-30 20:35:07 +00:00
2017-09-21 23:40:19 +00:00
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*/ ] ) ;
2017-06-01 19:32:44 +00:00
2015-09-17 06:09:10 +00:00
2017-09-21 23:40:19 +00:00
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 ) ;
2017-06-07 16:37:28 +00:00
2017-09-21 23:40:19 +00:00
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 ) ;
2017-01-17 02:17:18 +00:00
2017-09-21 23:40:19 +00:00
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 ) ;
2017-05-27 01:14:38 +00:00
2016-10-05 23:31:48 +00:00
2016-10-23 14:14:50 +00:00
//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
2017-09-21 23:40:19 +00:00
B3_SHARED_API int b3PhysicsParamSetInternalSimFlags ( b3SharedMemoryCommandHandle commandHandle , int flags ) ;
2016-10-05 23:31:48 +00:00
2015-07-31 06:22:44 +00:00
2017-09-21 06:18:18 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3InitStepSimulationCommand ( b3PhysicsClientHandle physClient ) ;
2015-07-31 06:22:44 +00:00
2017-09-21 06:18:18 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3InitResetSimulationCommand ( b3PhysicsClientHandle physClient ) ;
2015-08-28 00:51:31 +00:00
2016-04-14 00:09:48 +00:00
///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);
2017-09-21 06:18:18 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3LoadUrdfCommandInit ( b3PhysicsClientHandle physClient , const char * urdfFileName ) ;
2016-04-14 00:09:48 +00:00
2017-09-21 06:18:18 +00:00
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 ) ;
2017-08-14 21:59:41 +00:00
2016-09-28 18:17:11 +00:00
2017-09-21 23:40:19 +00:00
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 ) ;
2016-11-12 02:07:42 +00:00
2015-07-31 06:22:44 +00:00
2016-08-10 01:40:12 +00:00
///compute the forces to achieve an acceleration, given a state q and qdot using inverse dynamics
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3CalculateInverseDynamicsCommandInit ( b3PhysicsClientHandle physClient , int bodyIndex ,
2016-08-10 01:40:12 +00:00
const double * jointPositionsQ , const double * jointVelocitiesQdot , const double * jointAccelerations ) ;
2017-09-21 23:40:19 +00:00
B3_SHARED_API int b3GetStatusInverseDynamicsJointForces ( b3SharedMemoryStatusHandle statusHandle ,
2016-08-10 01:40:12 +00:00
int * bodyUniqueId ,
int * dofCount ,
double * jointForces ) ;
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3CalculateJacobianCommandInit ( b3PhysicsClientHandle physClient , int bodyIndex , int linkIndex , const double * localPosition , const double * jointPositionsQ , const double * jointVelocitiesQdot , const double * jointAccelerations ) ;
2016-09-07 23:00:38 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API int b3GetStatusJacobian ( b3SharedMemoryStatusHandle statusHandle , double * linearJacobian , double * angularJacobian ) ;
2016-08-10 01:40:12 +00:00
2016-09-08 22:15:58 +00:00
///compute the joint positions to move the end effector to a desired target using inverse kinematics
2017-09-21 23:40:19 +00:00
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 ,
2016-09-08 22:15:58 +00:00
int * bodyUniqueId ,
int * dofCount ,
double * jointPositions ) ;
2017-09-21 23:40:19 +00:00
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 ) ;
2017-08-14 21:59:41 +00:00
2016-06-04 02:03:56 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3SaveWorldCommandInit ( b3PhysicsClientHandle physClient , const char * sdfFileName ) ;
2016-10-13 06:03:36 +00:00
2016-06-23 15:40:36 +00:00
///The b3JointControlCommandInit method is obsolete, use b3JointControlCommandInit2 instead
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3JointControlCommandInit ( b3PhysicsClientHandle physClient , int controlMode ) ;
2016-06-23 15:40:36 +00:00
2016-06-24 14:31:17 +00:00
///Set joint motor control variables such as desired position/angle, desired velocity,
2015-08-02 21:00:43 +00:00
///applied joint forces, dependent on the control mode (CONTROL_MODE_VELOCITY or CONTROL_MODE_TORQUE)
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3JointControlCommandInit2 ( b3PhysicsClientHandle physClient , int bodyUniqueId , int controlMode ) ;
2016-06-23 15:40:36 +00:00
2016-06-24 14:31:17 +00:00
///Only use when controlMode is CONTROL_MODE_POSITION_VELOCITY_PD
2017-09-21 23:40:19 +00:00
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 ) ;
2016-06-24 14:31:17 +00:00
///Only use when controlMode is CONTROL_MODE_VELOCITY
2017-09-21 23:40:19 +00:00
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 ) ;
2015-08-02 21:00:43 +00:00
///Only use if when controlMode is CONTROL_MODE_TORQUE,
2017-09-21 23:40:19 +00:00
B3_SHARED_API int b3JointControlSetDesiredForceTorque ( b3SharedMemoryCommandHandle commandHandle , int dofIndex , double value ) ;
2015-08-02 21:00:43 +00:00
///the creation of collision shapes and rigid bodies etc is likely going to change,
///but good to have a b3CreateBoxShapeCommandInit for now
2017-06-03 17:57:56 +00:00
2017-09-21 23:40:19 +00:00
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 ) ;
2017-06-03 17:57:56 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API void b3CreateCollisionShapeSetChildTransform ( b3SharedMemoryCommandHandle commandHandle , int shapeIndex , double childPosition [ /*3*/ ] , double childOrientation [ /*4*/ ] ) ;
2017-06-03 17:57:56 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API int b3GetStatusCollisionShapeUniqueId ( b3SharedMemoryStatusHandle statusHandle ) ;
2017-06-03 17:57:56 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3CreateVisualShapeCommandInit ( b3PhysicsClientHandle physClient ) ;
B3_SHARED_API int b3GetStatusVisualShapeUniqueId ( b3SharedMemoryStatusHandle statusHandle ) ;
2017-06-03 17:57:56 +00:00
2017-09-21 23:40:19 +00:00
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*/ ] ) ;
2017-06-03 17:57:56 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API int b3CreateMultiBodyLink ( b3SharedMemoryCommandHandle commandHandle , double linkMass , double linkCollisionShapeIndex ,
2017-06-19 17:14:26 +00:00
double linkVisualShapeIndex ,
2017-09-21 06:18:18 +00:00
double linkPosition [ /*3*/ ] ,
double linkOrientation [ /*4*/ ] ,
double linkInertialFramePosition [ /*3*/ ] ,
double linkInertialFrameOrientation [ /*4*/ ] ,
2017-06-19 17:14:26 +00:00
int linkParentIndex ,
int linkJointType ,
2017-09-21 06:18:18 +00:00
double linkJointAxis [ /*3*/ ] ) ;
2017-06-19 17:14:26 +00:00
2017-06-05 05:04:16 +00:00
//useMaximalCoordinates are disabled by default, enabling them is experimental and not fully supported yet
2017-09-21 23:40:19 +00:00
B3_SHARED_API void b3CreateMultiBodyUseMaximalCoordinates ( b3SharedMemoryCommandHandle commandHandle ) ;
2017-06-03 17:57:56 +00:00
2017-06-05 05:04:16 +00:00
//int b3CreateMultiBodyAddLink(b3SharedMemoryCommandHandle commandHandle, int jointType, int parentLinkIndex, double linkMass, int linkCollisionShapeUnique, int linkVisualShapeUniqueId);
2017-06-03 17:57:56 +00:00
2016-04-13 20:06:15 +00:00
///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
2017-09-21 23:40:19 +00:00
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 ) ;
2015-10-27 21:55:46 +00:00
2015-10-14 05:23:28 +00:00
2016-04-14 00:09:48 +00:00
///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.
2017-09-21 23:40:19 +00:00
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*/ ] ) ;
2016-11-28 23:11:34 +00:00
2017-09-21 23:40:19 +00:00
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 ) ;
2015-08-02 21:00:43 +00:00
2017-09-21 23:40:19 +00:00
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 ) ;
2017-03-23 17:29:16 +00:00
2016-04-14 00:09:48 +00:00
///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.
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3CreateSensorCommandInit ( b3PhysicsClientHandle physClient , int bodyUniqueId ) ;
B3_SHARED_API int b3CreateSensorEnable6DofJointForceTorqueSensor ( b3SharedMemoryCommandHandle commandHandle , int jointIndex , int enable ) ;
2016-04-14 00:09:48 +00:00
///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.
2017-09-21 23:40:19 +00:00
B3_SHARED_API int b3CreateSensorEnableIMUForLink ( b3SharedMemoryCommandHandle commandHandle , int linkIndex , int enable ) ;
2015-08-02 21:00:43 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3RequestActualStateCommandInit ( b3PhysicsClientHandle physClient , int bodyUniqueId ) ;
B3_SHARED_API int b3RequestActualStateCommandComputeLinkVelocity ( b3SharedMemoryCommandHandle commandHandle , int computeLinkVelocity ) ;
2017-03-26 20:06:46 +00:00
2017-09-21 23:40:19 +00:00
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 ) ;
2015-09-25 05:42:22 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3PickBody ( b3PhysicsClientHandle physClient , double rayFromWorldX ,
2015-11-05 00:08:28 +00:00
double rayFromWorldY , double rayFromWorldZ ,
double rayToWorldX , double rayToWorldY , double rayToWorldZ ) ;
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3MovePickedBody ( b3PhysicsClientHandle physClient , double rayFromWorldX ,
2015-11-05 00:08:28 +00:00
double rayFromWorldY , double rayFromWorldZ ,
double rayToWorldX , double rayToWorldY ,
double rayToWorldZ ) ;
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3RemovePickingConstraint ( b3PhysicsClientHandle physClient ) ;
2015-07-23 01:06:05 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3CreateRaycastCommandInit ( b3PhysicsClientHandle physClient , double rayFromWorldX ,
2016-12-27 03:40:09 +00:00
double rayFromWorldY , double rayFromWorldZ ,
double rayToWorldX , double rayToWorldY , double rayToWorldZ ) ;
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3CreateRaycastBatchCommandInit ( b3PhysicsClientHandle physClient ) ;
B3_SHARED_API void b3RaycastBatchAddRay ( b3SharedMemoryCommandHandle commandHandle , const double rayFromWorld [ /*3*/ ] , const double rayToWorld [ /*3*/ ] ) ;
2017-04-05 22:21:26 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API void b3GetRaycastInformation ( b3PhysicsClientHandle physClient , struct b3RaycastInformation * raycastInfo ) ;
2016-12-27 03:40:09 +00:00
2016-06-27 01:18:30 +00:00
/// Apply external force at the body (or link) center of mass, in world space/Cartesian coordinates.
2017-09-21 23:40:19 +00:00
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 ) ;
2017-01-23 03:08:31 +00:00
2016-11-12 02:07:42 +00:00
///experiments of robots interacting with non-rigid objects (such as btSoftBody)
2017-09-21 23:40:19 +00:00
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 ) ;
2016-06-27 01:18:30 +00:00
2016-12-27 03:40:09 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3RequestVREventsCommandInit ( b3PhysicsClientHandle physClient ) ;
B3_SHARED_API void b3VREventsSetDeviceTypeFilter ( b3SharedMemoryCommandHandle commandHandle , int deviceTypeFilter ) ;
2017-04-08 05:53:36 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API void b3GetVREventsData ( b3PhysicsClientHandle physClient , struct b3VREventsData * vrEventsData ) ;
2016-12-27 03:40:09 +00:00
2017-09-21 23:40:19 +00:00
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 ) ;
2017-01-06 01:41:58 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3RequestKeyboardEventsCommandInit ( b3PhysicsClientHandle physClient ) ;
B3_SHARED_API void b3GetKeyboardEventsData ( b3PhysicsClientHandle physClient , struct b3KeyboardEventsData * keyboardEventsData ) ;
2017-03-02 20:33:22 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3RequestMouseEventsCommandInit ( b3PhysicsClientHandle physClient ) ;
B3_SHARED_API void b3GetMouseEventsData ( b3PhysicsClientHandle physClient , struct b3MouseEventsData * mouseEventsData ) ;
2017-06-17 20:29:14 +00:00
2017-09-21 23:40:19 +00:00
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 ) ;
2017-03-04 23:30:57 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API int b3GetStatusLoggingUniqueId ( b3SharedMemoryStatusHandle statusHandle ) ;
B3_SHARED_API int b3StateLoggingStop ( b3SharedMemoryCommandHandle commandHandle , int loggingUniqueId ) ;
2016-12-27 03:40:09 +00:00
2017-03-04 23:30:57 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3ProfileTimingCommandInit ( b3PhysicsClientHandle physClient , const char * name ) ;
B3_SHARED_API void b3SetProfileTimingDuractionInMicroSeconds ( b3SharedMemoryCommandHandle commandHandle , int duration ) ;
2017-03-04 23:30:57 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API void b3SetTimeOut ( b3PhysicsClientHandle physClient , double timeOutInSeconds ) ;
B3_SHARED_API double b3GetTimeOut ( b3PhysicsClientHandle physClient ) ;
2017-02-24 23:34:11 +00:00
2017-09-21 23:40:19 +00:00
B3_SHARED_API b3SharedMemoryCommandHandle b3SetAdditionalSearchPath ( b3PhysicsClientHandle physClient , char * path ) ;
2017-08-28 02:34:00 +00:00
2017-09-21 23:40:19 +00:00
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*/ ] ) ;
2017-02-24 23:34:11 +00:00
2015-07-23 01:06:05 +00:00
# ifdef __cplusplus
}
# endif
# endif //PHYSICS_CLIENT_C_API_H