diff --git a/data/l_finger_collision.stl b/data/l_finger_collision.stl
new file mode 100644
index 000000000..b12b2dd9a
Binary files /dev/null and b/data/l_finger_collision.stl differ
diff --git a/data/pr2_gripper.urdf b/data/pr2_gripper.urdf
index 47f8c8a39..1ec2cf3ff 100644
--- a/data/pr2_gripper.urdf
+++ b/data/pr2_gripper.urdf
@@ -17,7 +17,7 @@
-
+
@@ -32,7 +32,7 @@
-
+
@@ -41,8 +41,14 @@
+
+
+
+
+
+
-
+
@@ -54,7 +60,7 @@
-
+
@@ -65,12 +71,12 @@
-
+
-
+
-
+
@@ -85,8 +91,8 @@
-
-
+
+
@@ -94,6 +100,12 @@
+
+
+
+
+
+
@@ -107,8 +119,8 @@
-
-
+
+
@@ -118,9 +130,9 @@
-
+
-
+
diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp
index 332d737ed..57cb56185 100644
--- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp
+++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp
@@ -557,7 +557,7 @@ PhysicsServerCommandProcessor::PhysicsServerCommandProcessor()
m_data = new PhysicsServerCommandProcessorInternalData();
createEmptyDynamicsWorld();
- m_data->m_dynamicsWorld->getSolverInfo().m_linearSlop = 0.0;
+ m_data->m_dynamicsWorld->getSolverInfo().m_linearSlop = 0.0001;
}
@@ -596,8 +596,8 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld()
m_data->m_remoteDebugDrawer = new SharedMemoryDebugDrawer();
- m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, 0));
- m_data->m_dynamicsWorld->getSolverInfo().m_erp2 = 0.08;
+ m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, -10));
+ m_data->m_dynamicsWorld->getSolverInfo().m_erp2 = 0.04;
}
void PhysicsServerCommandProcessor::deleteCachedInverseDynamicsBodies()
@@ -2957,7 +2957,7 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)m_data->m_gripperMultiBody->getLink(i ).m_userPtr;
if (motor)
{
- motor->setErp(0.1);
+ motor->setErp(0.2);
btScalar posTarget = 0.1 + (1 - btMin(0.75,gVRGripperAnalog)*1.5)*SIMD_HALF_PI*0.29;
btScalar maxPosTarget = 0.55;
@@ -2972,7 +2972,7 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
motor->setPositionTarget(posTarget, 1);
motor->setVelocityTarget(0, 0.5);
- btScalar maxImp = 500*m_data->m_physicsDeltaTime;
+ btScalar maxImp = 1*m_data->m_physicsDeltaTime;
motor->setMaxAppliedImpulse(maxImp);
}
}
diff --git a/examples/StandaloneMain/hellovr_opengl_main.cpp b/examples/StandaloneMain/hellovr_opengl_main.cpp
index b0fd21d1a..485ee71ca 100644
--- a/examples/StandaloneMain/hellovr_opengl_main.cpp
+++ b/examples/StandaloneMain/hellovr_opengl_main.cpp
@@ -704,10 +704,10 @@ bool CMainApplication::HandleInput()
///todo(erwincoumans) can't use reguar debug drawer, because physics/graphics are not in sync
//so it can (and likely will) cause crashes
//add a special debug drawer that deals with this
- // gDebugDrawFlags = btIDebugDraw::DBG_DrawWireframe+btIDebugDraw::DBG_DrawContactPoints+
- // btIDebugDraw::DBG_DrawConstraintLimits+
- // btIDebugDraw::DBG_DrawConstraints
- // ;
+ //gDebugDrawFlags = btIDebugDraw::DBG_DrawWireframe+btIDebugDraw::DBG_DrawContactPoints+
+ //btIDebugDraw::DBG_DrawConstraintLimits+
+ //btIDebugDraw::DBG_DrawConstraints
+ //;
}
sExample->vrControllerButtonCallback(unDevice, button, 1, pos, orn);