Merge pull request #1919 from erwincoumans/master

btMultiBody: fix indexing issue causing wrong friction to be reported, remove obsolete BT_PYBULLET_GRPC and PYBULLET_EGL
This commit is contained in:
erwincoumans
2018-10-06 19:02:09 -07:00
committed by GitHub
3 changed files with 40 additions and 18 deletions

View File

@@ -0,0 +1,34 @@
import pybullet as p
p.connect(p.GUI)
useMaximalCoordinates = False
p.loadURDF("plane.urdf", useMaximalCoordinates=useMaximalCoordinates )
#p.loadURDF("sphere2.urdf",[0,0,1])
p.loadURDF("cube.urdf",[0,0,1], useMaximalCoordinates=useMaximalCoordinates )
p.setGravity(0,3,-10)
while(1):
p.stepSimulation()
pts = p.getContactPoints()
print("num pts=",len(pts))
totalNormalForce = 0
totalFrictionForce = [0,0,0]
totalLateralFrictionForce=[0,0,0]
for pt in pts:
#print("pt.normal=",pt[7])
#print("pt.normalForce=",pt[9])
totalNormalForce += pt[9]
#print("pt.lateralFrictionA=",pt[10])
#print("pt.lateralFrictionADir=",pt[11])
#print("pt.lateralFrictionB=",pt[12])
#print("pt.lateralFrictionBDir=",pt[13])
totalLateralFrictionForce[0]+=pt[11][0]*pt[10]+pt[13][0]*pt[12]
totalLateralFrictionForce[1]+=pt[11][1]*pt[10]+pt[13][1]*pt[12]
totalLateralFrictionForce[2]+=pt[11][2]*pt[10]+pt[13][2]*pt[12]
print("totalNormalForce=",totalNormalForce)
print("totalLateralFrictionForce=",totalLateralFrictionForce)

View File

@@ -9704,30 +9704,14 @@ PyMODINIT_FUNC
#if PY_MAJOR_VERSION >= 3 #if PY_MAJOR_VERSION >= 3
PyInit_pybullet(void) PyInit_pybullet(void)
#else #else
#ifdef BT_USE_EGL2
initpybullet_egl(void)
#else
#ifdef BT_PYBULLET_GRPC
initpybullet_grpc(void)
#else
initpybullet(void) initpybullet(void)
#endif //BT_USE_EGL2
#endif //BT_PYBULLET_GRPC
#endif #endif
{ {
PyObject* m; PyObject* m;
#if PY_MAJOR_VERSION >= 3 #if PY_MAJOR_VERSION >= 3
m = PyModule_Create(&moduledef); m = PyModule_Create(&moduledef);
#else
#ifdef BT_USE_EGL2
m = Py_InitModule3("pybullet_egl", SpamMethods, "Python bindings for Bullet");
#else
#ifdef BT_PYBULLET_GRPC
m = Py_InitModule3("pybullet_grpc", SpamMethods, "Python bindings for Bullet");
#else #else
m = Py_InitModule3("pybullet", SpamMethods, "Python bindings for Bullet"); m = Py_InitModule3("pybullet", SpamMethods, "Python bindings for Bullet");
#endif //BT_USE_EGL2
#endif //BT_PYBULLET_GRPC
#endif #endif
#if PY_MAJOR_VERSION >= 3 #if PY_MAJOR_VERSION >= 3

View File

@@ -1232,7 +1232,7 @@ void btMultiBodyConstraintSolver::convertMultiBodyContact(btPersistentManifold*
/////setup the friction constraints /////setup the friction constraints
#define ENABLE_FRICTION #define ENABLE_FRICTION
#ifdef ENABLE_FRICTION #ifdef ENABLE_FRICTION
solverConstraint.m_frictionIndex = frictionIndex; solverConstraint.m_frictionIndex = m_multiBodyFrictionContactConstraints.size();
///Bullet has several options to set the friction directions ///Bullet has several options to set the friction directions
///By default, each contact has only a single friction direction that is recomputed automatically every frame ///By default, each contact has only a single friction direction that is recomputed automatically every frame
@@ -1501,9 +1501,13 @@ btScalar btMultiBodyConstraintSolver::solveGroupCacheFriendlyFinish(btCollisionO
if ((infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS)) if ((infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS))
{ {
pt->m_appliedImpulseLateral2 = m_multiBodyFrictionContactConstraints[solverConstraint.m_frictionIndex + 1].m_appliedImpulse; pt->m_appliedImpulseLateral2 = m_multiBodyFrictionContactConstraints[solverConstraint.m_frictionIndex + 1].m_appliedImpulse;
} else
{
pt->m_appliedImpulseLateral2 = 0;
} }
//do a callback here?
} }
//do a callback here?
} }
#if 0 #if 0
//multibody joint feedback //multibody joint feedback