Crate rubullet_sys[][src]

Foreign function interface for Bullet C API.

Structs

b3AABBOverlapData
b3BodyInfo
b3CameraImageData
b3ContactInformation
b3ContactPointData
b3DynamicsInfo
b3JointInfo
b3JointSensorState
b3JointSensorState2
b3KeyboardEvent
b3KeyboardEventsData
b3LinkState
b3MouseEvent
b3MouseEventsData
b3OpenGLVisualizerCameraInfo
b3OverlappingObject
b3PhysicsClientHandle__
b3PhysicsSimulationParameters
b3RayHitInfo
b3RaycastInformation
b3SharedMemoryCommandHandle__
b3SharedMemoryStatusHandle__
b3UserConstraint
b3UserConstraintState
b3VisualShapeData
b3VisualShapeInformation

Enums

EnumSharedMemoryServerStatus
eURDF_Flags

Constants

B3_MAX_NUM_INDICES
B3_MAX_NUM_VERTICES
MAX_RAY_INTERSECTION_BATCH_SIZE_STREAMING
MAX_SDF_BODIES
SHARED_MEMORY_KEY

Functions

b3ApplyExternalForce
b3ApplyExternalForceCommandInit

Apply external force at the body (or link) center of mass, in world space/Cartesian coordinates.

b3ApplyExternalTorque
b3CalculateInverseDynamicsCommandInit2
b3CalculateInverseDynamicsSetFlags
b3CalculateInverseKinematicsAddTargetPositionWithOrientation
b3CalculateInverseKinematicsAddTargetPurePosition
b3CalculateInverseKinematicsAddTargetsPurePosition
b3CalculateInverseKinematicsCommandInit
b3CalculateInverseKinematicsPosOrnWithNullSpaceVel
b3CalculateInverseKinematicsPosWithNullSpaceVel
b3CalculateInverseKinematicsSelectSolver
b3CalculateInverseKinematicsSetCurrentPositions
b3CalculateInverseKinematicsSetJointDamping
b3CalculateInverseKinematicsSetMaxNumIterations
b3CalculateInverseKinematicsSetResidualThreshold
b3CalculateJacobianCommandInit
b3CalculateMassMatrixCommandInit
b3CalculateMassMatrixSetFlags
b3CanSubmitCommand
b3ChangeDynamicsInfoSetActivationState
b3ChangeDynamicsInfoSetAngularDamping
b3ChangeDynamicsInfoSetAnisotropicFriction
b3ChangeDynamicsInfoSetCcdSweptSphereRadius
b3ChangeDynamicsInfoSetCollisionMargin
b3ChangeDynamicsInfoSetContactProcessingThreshold
b3ChangeDynamicsInfoSetContactStiffnessAndDamping
b3ChangeDynamicsInfoSetDynamicType
b3ChangeDynamicsInfoSetFrictionAnchor
b3ChangeDynamicsInfoSetJointDamping
b3ChangeDynamicsInfoSetJointLimit
b3ChangeDynamicsInfoSetJointLimitForce
b3ChangeDynamicsInfoSetLateralFriction
b3ChangeDynamicsInfoSetLinearDamping
b3ChangeDynamicsInfoSetLocalInertiaDiagonal
b3ChangeDynamicsInfoSetMass
b3ChangeDynamicsInfoSetMaxJointVelocity
b3ChangeDynamicsInfoSetRestitution
b3ChangeDynamicsInfoSetRollingFriction
b3ChangeDynamicsInfoSetSpinningFriction
b3CollisionFilterCommandInit
b3ComputeDofCount
b3ComputePositionFromViewMatrix
b3ComputeProjectionMatrix
b3ComputeProjectionMatrixFOV
b3ComputeViewMatrixFromPositions
b3ComputeViewMatrixFromYawPitchRoll
b3ConfigureOpenGLVisualizerSetViewMatrix
b3ConfigureOpenGLVisualizerSetVisualizationFlags
b3ConnectPhysicsDirect
b3ConnectPhysicsTCP
b3ConnectPhysicsUDP
b3ConnectSharedMemory
b3CreateChangeTextureCommandInit
b3CreateCollisionSetFlag
b3CreateCollisionShapeAddBox
b3CreateCollisionShapeAddCapsule
b3CreateCollisionShapeAddConcaveMesh
b3CreateCollisionShapeAddConvexMesh
b3CreateCollisionShapeAddCylinder
b3CreateCollisionShapeAddHeightfield
b3CreateCollisionShapeAddHeightfield2
b3CreateCollisionShapeAddMesh
b3CreateCollisionShapeAddPlane
b3CreateCollisionShapeAddSphere
b3CreateCollisionShapeCommandInit

the creation of collision shapes and rigid bodies etc is likely going to change, but good to have a b3CreateBoxShapeCommandInit for now

b3CreateCollisionShapeSetChildTransform
b3CreateInProcessGraphicsServerAndConnectMainThreadSharedMemory
b3CreateInProcessGraphicsServerAndConnectSharedMemory
b3CreateInProcessPhysicsServerAndConnect
b3CreateInProcessPhysicsServerAndConnectMainThread
b3CreateInProcessPhysicsServerAndConnectMainThreadSharedMemory
b3CreateInProcessPhysicsServerAndConnectSharedMemory
b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect3
b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect4
b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnectTCP
b3CreateMultiBodyBase
b3CreateMultiBodyCommandInit
b3CreateMultiBodyLink
b3CreateMultiBodySetBatchPositions
b3CreateMultiBodySetFlags
b3CreateMultiBodyUseMaximalCoordinates
b3CreatePoseCommandInit
b3CreatePoseCommandSetBaseAngularVelocity
b3CreatePoseCommandSetBaseLinearVelocity
b3CreatePoseCommandSetBaseOrientation
b3CreatePoseCommandSetBasePosition
b3CreatePoseCommandSetJointPosition
b3CreatePoseCommandSetJointVelocity
b3CreateRaycastBatchCommandInit
b3CreateRaycastCommandInit
b3CreateSensorCommandInit

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.

b3CreateSensorEnable6DofJointForceTorqueSensor
b3CreateVisualSetFlag
b3CreateVisualShapeAddBox
b3CreateVisualShapeAddCapsule
b3CreateVisualShapeAddCylinder
b3CreateVisualShapeAddMesh
b3CreateVisualShapeAddMesh2
b3CreateVisualShapeAddPlane
b3CreateVisualShapeAddSphere
b3CreateVisualShapeCommandInit
b3CreateVisualShapeSetChildTransform
b3CreateVisualShapeSetRGBAColor
b3CreateVisualShapeSetSpecularColor
b3DisconnectSharedMemory
b3GetAABBOverlapResults
b3GetBodyInfo

given a body unique id, return the body information. See b3BodyInfo in SharedMemoryPublic.h

b3GetBodyUniqueId

return the body unique id, given the index in range [0 , b3GetNumBodies() )

b3GetCameraImageData
b3GetClosestPointInformation
b3GetContactPointInformation
b3GetDebugItemUniqueId
b3GetDynamicsInfo

given a body unique id and link index, return the dynamics information. See b3DynamicsInfo in SharedMemoryPublic.h

b3GetDynamicsInfoCommandInit
b3GetJointInfo
b3GetJointState
b3GetJointStateMultiDof
b3GetKeyboardEventsData
b3GetLinkState
b3GetMouseEventsData
b3GetNumBodies

return the total number of bodies in the simulation

b3GetNumJoints
b3GetNumUserConstraints
b3GetRaycastInformation
b3GetStatusAABB
b3GetStatusActualState
b3GetStatusBodyIndex
b3GetStatusBodyIndices
b3GetStatusCollisionShapeUniqueId
b3GetStatusDebugParameterValue
b3GetStatusGetStateId
b3GetStatusInverseDynamicsJointForces
b3GetStatusInverseKinematicsJointPositions
b3GetStatusJacobian
b3GetStatusLoggingUniqueId
b3GetStatusMassMatrix

the mass matrix is stored in column-major layout of size dofCount*dofCount

b3GetStatusOpenGLVisualizerCamera
b3GetStatusPhysicsSimulationParameters
b3GetStatusTextureUniqueId
b3GetStatusType
b3GetStatusUserConstraintState
b3GetStatusUserConstraintUniqueId

return a unique id for the user constraint, after successful creation, or -1 for an invalid constraint id

b3GetStatusVisualShapeUniqueId
b3GetTimeOut
b3GetUserConstraintId

return the user constraint id, given the index in range [0 , b3GetNumUserConstraints() )

b3GetUserConstraintInfo
b3GetVisualShapeInformation
b3InitAABBOverlapQuery

get all the bodies that touch a given axis aligned bounding box specified in world space (min and max coordinates)

b3InitChangeDynamicsInfo
b3InitChangeUserConstraintCommand

change parameters of an existing user constraint

b3InitChangeUserConstraintSetERP
b3InitChangeUserConstraintSetFrameInB
b3InitChangeUserConstraintSetGearAuxLink
b3InitChangeUserConstraintSetGearRatio
b3InitChangeUserConstraintSetMaxForce
b3InitChangeUserConstraintSetPivotInB
b3InitChangeUserConstraintSetRelativePositionTarget
b3InitClosestDistanceQuery

compute the closest points between two bodies

b3InitConfigureOpenGLVisualizer
b3InitCreateSoftBodyAnchorConstraintCommand
b3InitCreateUserConstraintCommand
b3InitDebugDrawingCommand
b3InitGetUserConstraintStateCommand
b3InitLoadTexture
b3InitPhysicsParamCommand
b3InitPhysicsParamCommand2
b3InitRemoveBodyCommand
b3InitRemoveCollisionShapeCommand
b3InitRemoveStateCommand
b3InitRemoveUserConstraintCommand
b3InitRequestCameraImage

request an image from a simulated camera, using a software renderer.

b3InitRequestCameraImage2
b3InitRequestCollisionShapeInformation
b3InitRequestContactPointInformation

request an contact point information

b3InitRequestOpenGLVisualizerCameraCommand
b3InitRequestPhysicsParamCommand
b3InitRequestVisualShapeInformation
b3InitResetSimulationCommand
b3InitResetSimulationCommand2
b3InitResetSimulationSetFlags
b3InitStepSimulationCommand
b3InitSyncBodyInfoCommand
b3InitSyncUserDataCommand
b3InitUpdateVisualShape
b3InitUpdateVisualShape2
b3InitUserDebugAddParameter
b3InitUserDebugDrawAddLine3D

Add/remove user-specific debug lines and debug text messages

b3InitUserDebugDrawAddText3D
b3InitUserDebugDrawRemove
b3InitUserDebugDrawRemoveAll
b3InitUserDebugReadParameter
b3JointControlCommandInit2
b3JointControlSetDesiredForceTorque
b3JointControlSetDesiredPosition
b3JointControlSetDesiredVelocity
b3JointControlSetKd
b3JointControlSetKp
b3JointControlSetMaximumForce
b3JointControlSetMaximumVelocity
b3LoadBulletCommandInit
b3LoadMJCFCommandInit
b3LoadMJCFCommandInit2
b3LoadMJCFCommandSetFlags
b3LoadSdfCommandInit
b3LoadSdfCommandSetUseGlobalScaling
b3LoadSdfCommandSetUseMultiBody
b3LoadSoftBodyAddCorotatedForce
b3LoadSoftBodyAddGravityForce
b3LoadSoftBodyAddMassSpringForce
b3LoadSoftBodyAddNeoHookeanForce
b3LoadSoftBodyCommandInit

experiments of robots interacting with non-rigid objects (such as btSoftBody)

b3LoadSoftBodySetCollisionHardness
b3LoadSoftBodySetCollisionMargin
b3LoadSoftBodySetFrictionCoefficient
b3LoadSoftBodySetMass
b3LoadSoftBodySetRepulsionStiffness
b3LoadSoftBodySetScale
b3LoadSoftBodySetSelfCollision
b3LoadSoftBodySetStartOrientation
b3LoadSoftBodySetStartPosition
b3LoadSoftBodyUpdateSimMesh
b3LoadSoftBodyUseAllDirectionDampingSprings
b3LoadSoftBodyUseBendingSprings
b3LoadSoftBodyUseFaceContact
b3LoadStateCommandInit
b3LoadStateSetFileName
b3LoadStateSetStateId
b3LoadUrdfCommandInit
b3LoadUrdfCommandSetFlags
b3LoadUrdfCommandSetGlobalScaling
b3LoadUrdfCommandSetStartOrientation
b3LoadUrdfCommandSetStartPosition
b3LoadUrdfCommandSetUseFixedBase
b3LoadUrdfCommandSetUseMultiBody
b3PhysicsParamSetArticulatedWarmStartingFactor
b3PhysicsParamSetCollisionFilterMode
b3PhysicsParamSetContactBreakingThreshold
b3PhysicsParamSetContactSlop
b3PhysicsParamSetDefaultContactERP
b3PhysicsParamSetDefaultFrictionCFM
b3PhysicsParamSetDefaultFrictionERP
b3PhysicsParamSetDefaultGlobalCFM
b3PhysicsParamSetDefaultNonContactERP
b3PhysicsParamSetEnableConeFriction
b3PhysicsParamSetEnableFileCaching
b3PhysicsParamSetGravity
b3PhysicsParamSetInternalSimFlags
b3PhysicsParamSetMaxNumCommandsPer1ms
b3PhysicsParamSetNumNonContactInnerIterations
b3PhysicsParamSetNumSolverIterations
b3PhysicsParamSetNumSubSteps
b3PhysicsParamSetRealTimeSimulation
b3PhysicsParamSetRestitutionVelocityThreshold
b3PhysicsParamSetSolverAnalytics
b3PhysicsParamSetSolverResidualThreshold
b3PhysicsParamSetSplitImpulsePenetrationThreshold
b3PhysicsParamSetTimeStep
b3PhysicsParamSetUseSplitImpulse
b3PhysicsParamSetWarmStartingFactor
b3PhysicsParameterSetAllowedCcdPenetration
b3PhysicsParameterSetConstraintSolverType
b3PhysicsParameterSetDeterministicOverlappingPairs
b3PhysicsParameterSetEnableSAT
b3PhysicsParameterSetJointFeedbackMode
b3PhysicsParameterSetMinimumSolverIslandSize
b3PhysicsParameterSetSparseSdfVoxelSize
b3PopProfileTiming
b3ProfileTimingCommandInit
b3PushProfileTiming
b3RaycastBatchAddRay
b3RaycastBatchAddRays
b3RaycastBatchSetCollisionFilterMask
b3RaycastBatchSetFractionEpsilon
b3RaycastBatchSetNumThreads
b3RaycastBatchSetParentObject
b3RaycastBatchSetReportHitNumber
b3RemoveDebugObjectColor
b3RequestActualStateCommandComputeForwardKinematics
b3RequestActualStateCommandComputeLinkVelocity
b3RequestActualStateCommandInit
b3RequestCameraImageSelectRenderer
b3RequestCameraImageSetCameraMatrices
b3RequestCameraImageSetFlags
b3RequestCameraImageSetLightAmbientCoeff
b3RequestCameraImageSetLightColor
b3RequestCameraImageSetLightDiffuseCoeff
b3RequestCameraImageSetLightDirection
b3RequestCameraImageSetLightDistance
b3RequestCameraImageSetLightSpecularCoeff
b3RequestCameraImageSetPixelResolution
b3RequestCameraImageSetProjectiveTextureMatrices

set projective texture camera matrices.

b3RequestCameraImageSetShadow
b3RequestCollisionInfoCommandInit
b3RequestKeyboardEventsCommandInit
b3RequestMouseEventsCommandInit
b3SaveBulletCommandInit
b3SaveStateCommandInit
b3SaveWorldCommandInit
b3SetAdditionalSearchPath
b3SetClosestDistanceFilterBodyA
b3SetClosestDistanceFilterBodyB
b3SetClosestDistanceFilterCollisionShapeA
b3SetClosestDistanceFilterCollisionShapeB
b3SetClosestDistanceFilterCollisionShapeOrientationA
b3SetClosestDistanceFilterCollisionShapeOrientationB
b3SetClosestDistanceFilterCollisionShapePositionA
b3SetClosestDistanceFilterCollisionShapePositionB
b3SetClosestDistanceFilterLinkA
b3SetClosestDistanceFilterLinkB
b3SetClosestDistanceThreshold
b3SetCollisionFilterGroupMask
b3SetCollisionFilterPair
b3SetContactFilterBodyA
b3SetContactFilterBodyB
b3SetContactFilterLinkA
b3SetContactFilterLinkB
b3SetDebugObjectColor
b3SetProfileTimingDuractionInMicroSeconds
b3SetProfileTimingType
b3SetTimeOut
b3StateLoggingAddLoggingObjectUniqueId
b3StateLoggingCommandInit
b3StateLoggingSetBodyAUniqueId
b3StateLoggingSetBodyBUniqueId
b3StateLoggingSetDeviceTypeFilter
b3StateLoggingSetLinkIndexA
b3StateLoggingSetLinkIndexB
b3StateLoggingSetLogFlags
b3StateLoggingSetMaxLogDof
b3StateLoggingStart
b3StateLoggingStop
b3SubmitClientCommandAndWaitStatus
b3UpdateVisualShapeFlags
b3UpdateVisualShapeRGBAColor
b3UpdateVisualShapeSpecularColor
b3UpdateVisualShapeTexture
b3UserDebugItemSetParentObject
b3UserDebugItemSetReplaceItemUniqueId
b3UserDebugTextSetOptionFlags
b3UserDebugTextSetOrientation

Type Definitions

b3PhysicsClientHandle
b3SharedMemoryCommandHandle
b3SharedMemoryStatusHandle