Regular API function

simGetContactInfo / sim.getContactInfo

Description Retrieves contact point information of a dynamic simulation pass.
C/C++
synopsis
simInt simGetContactInfo(simInt dynamicPass,simInt objectHandle,simInt index,simInt* objectHandles,simFloat* contactInfo)
C/C++
parameters
dynamicPass: a specific dynamic sub-step index or sim.handle_all. By default a call to simHandleDynamics executes the dynamics engine x times, with x times smaller time steps (where x is a parameter that can be adjusted). At each of those sub-steps, contacts are created and destroyed. With the dynamicPass argument you can select which sub-step you wish to retrieve contacts from (zero-based index), or sim.handle_all to retrieve the contacts of all sub-steps. See also simGetInt32Param(sim.intparam_dynamic_step_divider).
objectHandle: handle of a specific object you wish to retrieve contacts from, or sim.handle_all to retrieve all contacts in the scene.
index: zero-based index of the contact to retrieve. Optionally, you may add sim.handleflag_extended to the index, if you also wish to retrieve the normal vector (see further down)
objectHandles: handles of the two objects contacting. The handles might also refer to particle objects that are not treated as regular scene objects.
contactInfo: pointer to 6 values (or 9 values if sim.handleflag_extended was added to index), where the 3 first values represent the contact position, the 3 next values represent the force generated by the contact, and the (optional) 3 last values represent the normal vector at the contact. The force vector returned by the Bullet engine will omit the component that results from fricition.
C/C++
return value
-1 in case of an error, 0 if no contact was found at the given index or 1 if a contact was returned.
Lua
synopsis
int[2] collidingObjects,float[3] collisionPoint,float[3] reactionForce,float[3] normalVector=sim.getContactInfo(int dynamicPass,int objectHandle,int index)
Lua
parameters
Similar to the C-function counterpart
Lua
return values
collidingObjects: handles of the two objects contacting. The handles might also refer to particle objects that are not treated as regular scene objects
collisionPoint: coordinates of the contact
reactionForce: vector that represents the force generated by the contact
normalVector: the normal vector at the contact point
Python
synopsis
list collidingObjects,list collisionPoint,list reactionForce,list normalVector=sim.getContactInfo(int dynamicPass,int objectHandle,int index)