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 ) ;
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"
# include "PhysicsClientUDP_C_API.h"
# 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.
2015-07-23 01:06:05 +00:00
void b3DisconnectSharedMemory ( b3PhysicsClientHandle physClient ) ;
2016-04-13 20:06:15 +00:00
///There can only be 1 outstanding command. Check if a command can be send.
2015-07-23 01:06:05 +00:00
int b3CanSubmitCommand ( b3PhysicsClientHandle physClient ) ;
2016-04-13 20:06:15 +00:00
///blocking submit command and wait for status
2015-09-17 16:37:44 +00:00
b3SharedMemoryStatusHandle b3SubmitClientCommandAndWaitStatus ( b3PhysicsClientHandle physClient , b3SharedMemoryCommandHandle commandHandle ) ;
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'.
2015-09-17 06:09:10 +00:00
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
b3SharedMemoryStatusHandle b3ProcessServerStatus ( b3PhysicsClientHandle physClient ) ;
2016-04-13 20:06:15 +00:00
/// Get the physics server return status type. See EnumSharedMemoryServerStatus in SharedMemoryPublic.h for error codes.
2015-09-17 16:37:44 +00:00
int b3GetStatusType ( b3SharedMemoryStatusHandle statusHandle ) ;
2016-06-13 17:11:28 +00:00
int b3GetStatusBodyIndices ( b3SharedMemoryStatusHandle statusHandle , int * bodyIndicesOut , int bodyIndicesCapacity ) ;
2015-10-13 18:32:25 +00:00
int b3GetStatusBodyIndex ( b3SharedMemoryStatusHandle statusHandle ) ;
2015-11-05 00:08:28 +00:00
int b3GetStatusActualState ( b3SharedMemoryStatusHandle statusHandle ,
int * bodyUniqueId ,
int * numDegreeOfFreedomQ ,
int * numDegreeOfFreedomU ,
const double * rootLocalInertialFrame [ ] ,
const double * actualStateQ [ ] ,
const double * actualStateQdot [ ] ,
const double * jointReactionForces [ ] ) ;
2016-09-27 19:13:45 +00:00
///return the total number of bodies in the simulation
int b3GetNumBodies ( b3PhysicsClientHandle physClient ) ;
/// return the body unique id, given the index in range [0 , b3GetNumBodies() )
int b3GetBodyUniqueId ( b3PhysicsClientHandle physClient , int serialIndex ) ;
///given a body unique id, return the body information. See b3BodyInfo in SharedMemoryPublic.h
int b3GetBodyInfo ( b3PhysicsClientHandle physClient , int bodyUniqueId , struct b3BodyInfo * info ) ;
2016-04-13 20:06:15 +00:00
///give a unique body index (after loading the body) return the number of joints.
2015-10-13 18:32:25 +00:00
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
int b3GetJointInfo ( b3PhysicsClientHandle physClient , int bodyIndex , int jointIndex , struct b3JointInfo * info ) ;
2016-08-23 01:14:29 +00:00
2016-11-14 22:08:05 +00:00
b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand ( b3PhysicsClientHandle physClient , int parentBodyIndex , int parentJointIndex , int childBodyIndex , int childJointIndex , struct b3JointInfo * info ) ;
int b3GetStatusUserConstraintUniqueId ( b3SharedMemoryStatusHandle statusHandle ) ;
b3SharedMemoryCommandHandle b3InitRemoveUserConstraintCommand ( b3PhysicsClientHandle physClient , int userConstraintUniqueId ) ;
2015-07-23 01:06:05 +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
2015-09-17 06:09:10 +00:00
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
2015-09-17 06:09:10 +00:00
void b3GetDebugLines ( b3PhysicsClientHandle physClient , struct b3DebugLines * lines ) ;
2016-05-18 06:57:19 +00:00
2016-11-14 15:39:34 +00:00
/// 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 b3InitUserDebugDrawAddText3D ( b3PhysicsClientHandle physClient , const char * txt , double positionXYZ [ 3 ] , double colorRGB [ 3 ] , double textSize , double lifeTime ) ;
b3SharedMemoryCommandHandle b3InitUserDebugDrawRemove ( b3PhysicsClientHandle physClient , int debugItemUniqueId ) ;
b3SharedMemoryCommandHandle b3InitUserDebugDrawRemoveAll ( b3PhysicsClientHandle physClient ) ;
2016-11-21 15:42:11 +00:00
b3SharedMemoryCommandHandle b3InitDebugDrawingCommand ( b3PhysicsClientHandle physClient ) ;
void b3SetDebugObjectColor ( b3SharedMemoryCommandHandle commandHandle , int objectUniqueId , int linkIndex , double objectColorRGB [ 3 ] ) ;
void b3RemoveDebugObjectColor ( b3SharedMemoryCommandHandle commandHandle , int objectUniqueId , int linkIndex ) ;
2016-11-14 15:39:34 +00:00
///All debug items unique Ids are positive: a negative unique Id means failure.
int b3GetDebugItemUniqueId ( b3SharedMemoryStatusHandle statusHandle ) ;
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.
b3SharedMemoryCommandHandle b3InitRequestCameraImage ( b3PhysicsClientHandle physClient ) ;
void b3RequestCameraImageSetCameraMatrices ( b3SharedMemoryCommandHandle command , float viewMatrix [ 16 ] , float projectionMatrix [ 16 ] ) ;
2016-11-17 23:15:52 +00:00
void b3RequestCameraImageSetPixelResolution ( b3SharedMemoryCommandHandle command , int width , int height ) ;
void b3RequestCameraImageSetLightDirection ( b3SharedMemoryCommandHandle commandHandle , const float lightDirection [ 3 ] ) ;
2016-11-20 20:52:12 +00:00
void b3RequestCameraImageSetLightColor ( b3SharedMemoryCommandHandle commandHandle , const float lightColor [ 3 ] ) ;
2016-11-29 21:19:35 +00:00
void b3RequestCameraImageSetLightDistance ( b3SharedMemoryCommandHandle commandHandle , float lightDistance ) ;
2016-12-06 23:21:35 +00:00
void b3RequestCameraImageSetLightAmbientCoeff ( b3SharedMemoryCommandHandle commandHandle , float lightAmbientCoeff ) ;
void b3RequestCameraImageSetLightDiffuseCoeff ( b3SharedMemoryCommandHandle commandHandle , float lightDiffuseCoeff ) ;
void b3RequestCameraImageSetLightSpecularCoeff ( b3SharedMemoryCommandHandle commandHandle , float lightSpecularCoeff ) ;
2016-11-29 22:10:07 +00:00
void b3RequestCameraImageSetShadow ( b3SharedMemoryCommandHandle commandHandle , int hasShadow ) ;
2016-11-17 23:15:52 +00:00
void b3RequestCameraImageSelectRenderer ( b3SharedMemoryCommandHandle commandHandle , int renderer ) ;
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 ] ) ;
///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 ] ) ;
/* obsolete, please use b3ComputeViewProjectionMatrices */
2016-06-16 18:48:37 +00:00
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 */
2016-08-08 21:23:44 +00:00
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 */
2016-06-16 18:48:37 +00:00
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 */
2016-07-08 21:29:58 +00:00
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
b3SharedMemoryCommandHandle b3InitRequestContactPointInformation ( b3PhysicsClientHandle physClient ) ;
void b3SetContactFilterBodyA ( b3SharedMemoryCommandHandle commandHandle , int bodyUniqueIdA ) ;
void b3SetContactFilterBodyB ( b3SharedMemoryCommandHandle commandHandle , int bodyUniqueIdB ) ;
2016-11-20 01:13:56 +00:00
void b3SetContactFilterLinkA ( b3SharedMemoryCommandHandle commandHandle , int linkIndexA ) ;
void b3SetContactFilterLinkB ( b3SharedMemoryCommandHandle commandHandle , int linkIndexB ) ;
2016-10-19 05:05:28 +00:00
void b3GetContactPointInformation ( b3PhysicsClientHandle physClient , struct b3ContactInformation * contactPointInfo ) ;
2016-11-10 05:01:04 +00:00
///compute the closest points between two bodies
b3SharedMemoryCommandHandle b3InitClosestDistanceQuery ( b3PhysicsClientHandle physClient ) ;
void b3SetClosestDistanceFilterBodyA ( b3SharedMemoryCommandHandle commandHandle , int bodyUniqueIdA ) ;
2016-11-20 01:13:56 +00:00
void b3SetClosestDistanceFilterLinkA ( b3SharedMemoryCommandHandle commandHandle , int linkIndexA ) ;
2016-11-10 05:01:04 +00:00
void b3SetClosestDistanceFilterBodyB ( b3SharedMemoryCommandHandle commandHandle , int bodyUniqueIdB ) ;
2016-11-20 01:13:56 +00:00
void b3SetClosestDistanceFilterLinkB ( b3SharedMemoryCommandHandle commandHandle , int linkIndexB ) ;
2016-11-10 05:01:04 +00:00
void b3SetClosestDistanceThreshold ( b3SharedMemoryCommandHandle commandHandle , double distance ) ;
void b3GetClosestPointInformation ( b3PhysicsClientHandle physClient , struct b3ContactInformation * contactPointInfo ) ;
///get all the bodies that touch a given axis aligned bounding box specified in world space (min and max coordinates)
b3SharedMemoryCommandHandle b3InitAABBOverlapQuery ( b3PhysicsClientHandle physClient , const double aabbMin [ 3 ] , const double aabbMax [ 3 ] ) ;
void b3GetAABBOverlapResults ( b3PhysicsClientHandle physClient , struct b3AABBOverlapData * data ) ;
2016-10-19 05:05:28 +00:00
//request visual shape information
b3SharedMemoryCommandHandle b3InitRequestVisualShapeInformation ( b3PhysicsClientHandle physClient , int bodyUniqueIdA ) ;
void b3GetVisualShapeInformation ( b3PhysicsClientHandle physClient , struct b3VisualShapeInformation * visualShapeInfo ) ;
2016-10-21 06:40:30 +00:00
b3SharedMemoryCommandHandle b3InitLoadTexture ( b3PhysicsClientHandle physClient , const char * filename ) ;
2016-10-21 18:55:27 +00:00
b3SharedMemoryCommandHandle b3InitUpdateVisualShape ( b3PhysicsClientHandle physClient , int bodyUniqueId , int jointIndex , int shapeIndex , int textureUniqueId ) ;
2015-09-17 06:09:10 +00:00
b3SharedMemoryCommandHandle b3InitPhysicsParamCommand ( b3PhysicsClientHandle physClient ) ;
int b3PhysicsParamSetGravity ( b3SharedMemoryCommandHandle commandHandle , double gravx , double gravy , double gravz ) ;
int b3PhysicsParamSetTimeStep ( b3SharedMemoryCommandHandle commandHandle , double timeStep ) ;
2016-09-08 22:15:58 +00:00
int b3PhysicsParamSetDefaultContactERP ( b3SharedMemoryCommandHandle commandHandle , double defaultContactERP ) ;
2016-08-24 21:25:06 +00:00
int b3PhysicsParamSetNumSubSteps ( b3SharedMemoryCommandHandle commandHandle , int numSubSteps ) ;
2016-07-18 06:50:11 +00:00
int b3PhysicsParamSetRealTimeSimulation ( b3SharedMemoryCommandHandle commandHandle , int enableRealTimeSimulation ) ;
2016-10-05 23:31:48 +00:00
int b3PhysicsParamSetNumSolverIterations ( b3SharedMemoryCommandHandle commandHandle , int numSolverIterations ) ;
2016-12-01 06:24:20 +00:00
int b3PhysicsParamSetUseSplitImpulse ( b3SharedMemoryCommandHandle commandHandle , int useSplitImpulse ) ;
int b3PhysicsParamSetSplitImpulsePenetrationThreshold ( b3SharedMemoryCommandHandle commandHandle , double splitImpulsePenetrationThreshold ) ;
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
int b3PhysicsParamSetInternalSimFlags ( b3SharedMemoryCommandHandle commandHandle , int flags ) ;
2016-10-05 23:31:48 +00:00
2015-07-31 06:22:44 +00:00
2015-09-17 06:09:10 +00:00
b3SharedMemoryCommandHandle b3InitStepSimulationCommand ( b3PhysicsClientHandle physClient ) ;
2015-07-31 06:22:44 +00:00
2015-09-17 06:09:10 +00:00
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);
2015-09-17 06:09:10 +00:00
b3SharedMemoryCommandHandle b3LoadUrdfCommandInit ( b3PhysicsClientHandle physClient , const char * urdfFileName ) ;
2016-04-14 00:09:48 +00:00
2015-09-17 06:09:10 +00:00
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 ) ;
2016-09-28 18:17:11 +00:00
2016-11-12 02:07:42 +00:00
b3SharedMemoryCommandHandle b3LoadBulletCommandInit ( b3PhysicsClientHandle physClient , const char * fileName ) ;
b3SharedMemoryCommandHandle b3SaveBulletCommandInit ( b3PhysicsClientHandle physClient , const char * fileName ) ;
b3SharedMemoryCommandHandle b3LoadMJCFCommandInit ( b3PhysicsClientHandle physClient , const char * fileName ) ;
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
b3SharedMemoryCommandHandle b3CalculateInverseDynamicsCommandInit ( b3PhysicsClientHandle physClient , int bodyIndex ,
const double * jointPositionsQ , const double * jointVelocitiesQdot , const double * jointAccelerations ) ;
int b3GetStatusInverseDynamicsJointForces ( b3SharedMemoryStatusHandle statusHandle ,
int * bodyUniqueId ,
int * dofCount ,
double * jointForces ) ;
2016-09-08 00:37:38 +00:00
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
2016-09-08 00:37:38 +00:00
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
2016-09-22 20:27:09 +00:00
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 ] ) ;
2016-09-30 08:03:40 +00:00
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 ) ;
2016-09-08 22:15:58 +00:00
int b3GetStatusInverseKinematicsJointPositions ( b3SharedMemoryStatusHandle statusHandle ,
int * bodyUniqueId ,
int * dofCount ,
double * jointPositions ) ;
2016-06-04 02:03:56 +00:00
b3SharedMemoryCommandHandle b3LoadSdfCommandInit ( b3PhysicsClientHandle physClient , const char * sdfFileName ) ;
2016-09-28 18:17:11 +00:00
int b3LoadSdfCommandSetUseMultiBody ( b3SharedMemoryCommandHandle commandHandle , int useMultiBody ) ;
2016-06-04 02:03:56 +00:00
2016-10-13 06:03:36 +00:00
b3SharedMemoryCommandHandle b3SaveWorldCommandInit ( b3PhysicsClientHandle physClient , const char * sdfFileName ) ;
2016-06-23 15:40:36 +00:00
///The b3JointControlCommandInit method is obsolete, use b3JointControlCommandInit2 instead
b3SharedMemoryCommandHandle b3JointControlCommandInit ( b3PhysicsClientHandle physClient , int controlMode ) ;
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)
2016-06-23 15:40:36 +00:00
b3SharedMemoryCommandHandle b3JointControlCommandInit2 ( b3PhysicsClientHandle physClient , int bodyUniqueId , int controlMode ) ;
2016-06-24 14:31:17 +00:00
///Only use when controlMode is CONTROL_MODE_POSITION_VELOCITY_PD
2015-09-25 05:42:22 +00:00
int b3JointControlSetDesiredPosition ( b3SharedMemoryCommandHandle commandHandle , int qIndex , double value ) ;
2015-09-17 06:09:10 +00:00
int b3JointControlSetKp ( b3SharedMemoryCommandHandle commandHandle , int dofIndex , double value ) ;
int b3JointControlSetKd ( b3SharedMemoryCommandHandle commandHandle , int dofIndex , double value ) ;
2016-06-24 14:31:17 +00:00
///Only use when controlMode is CONTROL_MODE_VELOCITY
2015-09-25 05:42:22 +00:00
int b3JointControlSetDesiredVelocity ( b3SharedMemoryCommandHandle commandHandle , int dofIndex , double value ) ; /* find a better name for dof/q/u indices, point to b3JointInfo */
2015-09-17 06:09:10 +00:00
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,
2015-09-17 06:09:10 +00:00
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
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
2015-09-17 06:09:10 +00:00
b3SharedMemoryCommandHandle b3CreateBoxShapeCommandInit ( b3PhysicsClientHandle physClient ) ;
int b3CreateBoxCommandSetStartPosition ( b3SharedMemoryCommandHandle commandHandle , double startPosX , double startPosY , double startPosZ ) ;
int b3CreateBoxCommandSetStartOrientation ( b3SharedMemoryCommandHandle commandHandle , double startOrnX , double startOrnY , double startOrnZ , double startOrnW ) ;
int b3CreateBoxCommandSetHalfExtents ( b3SharedMemoryCommandHandle commandHandle , double halfExtentsX , double halfExtentsY , double halfExtentsZ ) ;
2015-10-27 21:55:46 +00:00
int b3CreateBoxCommandSetMass ( b3SharedMemoryCommandHandle commandHandle , double mass ) ;
int b3CreateBoxCommandSetCollisionShapeType ( b3SharedMemoryCommandHandle commandHandle , int collisionShapeType ) ;
2015-11-07 01:11:15 +00:00
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.
2015-10-14 05:23:28 +00:00
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 ) ;
2016-11-28 23:11:34 +00:00
int b3CreatePoseCommandSetBaseLinearVelocity ( b3SharedMemoryCommandHandle commandHandle , double linVel [ 3 ] ) ;
int b3CreatePoseCommandSetBaseAngularVelocity ( b3SharedMemoryCommandHandle commandHandle , double angVel [ 3 ] ) ;
2015-10-15 15:15:22 +00:00
int b3CreatePoseCommandSetJointPositions ( b3SharedMemoryCommandHandle commandHandle , int numJointPositions , const double * jointPositions ) ;
2015-10-14 05:23:28 +00:00
int b3CreatePoseCommandSetJointPosition ( b3PhysicsClientHandle physClient , b3SharedMemoryCommandHandle commandHandle , int jointIndex , double jointPosition ) ;
2015-08-02 21:00:43 +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.
2016-06-17 01:46:34 +00:00
b3SharedMemoryCommandHandle b3CreateSensorCommandInit ( b3PhysicsClientHandle physClient , int bodyUniqueId ) ;
2015-09-25 05:42:22 +00:00
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.
2015-09-17 06:09:10 +00:00
int b3CreateSensorEnableIMUForLink ( b3SharedMemoryCommandHandle commandHandle , int linkIndex , int enable ) ;
2015-08-02 21:00:43 +00:00
2015-10-27 22:46:13 +00:00
b3SharedMemoryCommandHandle b3RequestActualStateCommandInit ( b3PhysicsClientHandle physClient , int bodyUniqueId ) ;
2015-09-25 05:50:34 +00:00
void b3GetJointState ( b3PhysicsClientHandle physClient , b3SharedMemoryStatusHandle statusHandle , int jointIndex , struct b3JointSensorState * state ) ;
2016-04-24 00:29:46 +00:00
void b3GetLinkState ( b3PhysicsClientHandle physClient , b3SharedMemoryStatusHandle statusHandle , int linkIndex , struct b3LinkState * state ) ;
2015-09-25 05:42:22 +00:00
2015-11-05 00:08:28 +00:00
b3SharedMemoryCommandHandle b3PickBody ( b3PhysicsClientHandle physClient , double rayFromWorldX ,
double rayFromWorldY , double rayFromWorldZ ,
double rayToWorldX , double rayToWorldY , double rayToWorldZ ) ;
b3SharedMemoryCommandHandle b3MovePickedBody ( b3PhysicsClientHandle physClient , double rayFromWorldX ,
double rayFromWorldY , double rayFromWorldZ ,
double rayToWorldX , double rayToWorldY ,
double rayToWorldZ ) ;
b3SharedMemoryCommandHandle b3RemovePickingConstraint ( b3PhysicsClientHandle physClient ) ;
2015-07-23 01:06:05 +00:00
2016-12-27 03:40:09 +00:00
b3SharedMemoryCommandHandle b3CreateRaycastCommandInit ( b3PhysicsClientHandle physClient , double rayFromWorldX ,
double rayFromWorldY , double rayFromWorldZ ,
double rayToWorldX , double rayToWorldY , double rayToWorldZ ) ;
void b3GetRaycastInformation ( b3PhysicsClientHandle physClient , struct b3RaycastInformation * raycastInfo ) ;
2016-06-27 01:18:30 +00:00
/// 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 ) ;
2016-10-17 20:01:04 +00:00
2016-11-12 02:07:42 +00:00
///experiments of robots interacting with non-rigid objects (such as btSoftBody)
2016-10-17 20:01:04 +00:00
b3SharedMemoryCommandHandle b3LoadBunnyCommandInit ( b3PhysicsClientHandle physClient ) ;
2016-11-01 23:45:10 +00:00
int b3LoadBunnySetScale ( b3SharedMemoryCommandHandle commandHandle , double scale ) ;
int b3LoadBunnySetMass ( b3SharedMemoryCommandHandle commandHandle , double mass ) ;
int b3LoadBunnySetCollisionMargin ( b3SharedMemoryCommandHandle commandHandle , double collisionMargin ) ;
2016-06-27 01:18:30 +00:00
2016-12-27 03:40:09 +00:00
b3SharedMemoryCommandHandle b3RequestVREventsCommandInit ( b3PhysicsClientHandle physClient ) ;
void b3GetVREventsData ( b3PhysicsClientHandle physClient , struct b3VREventsData * vrEventsData ) ;
2017-01-06 01:41:58 +00:00
b3SharedMemoryCommandHandle b3SetVRCameraStateCommandInit ( b3PhysicsClientHandle physClient ) ;
int b3SetVRCameraRootPosition ( b3SharedMemoryCommandHandle commandHandle , double rootPos [ 3 ] ) ;
int b3SetVRCameraRootOrientation ( b3SharedMemoryCommandHandle commandHandle , double rootOrn [ 4 ] ) ;
int b3SetVRCameraTrackingObject ( b3SharedMemoryCommandHandle commandHandle , int objectUniqueId ) ;
2016-12-27 03:40:09 +00:00
2015-07-23 01:06:05 +00:00
# ifdef __cplusplus
}
# endif
# endif //PHYSICS_CLIENT_C_API_H