rolling friction -> combine using rolling*normal friction, add for both objects.

rolling friction -> only along the normal, until we have separate rolling friction coefficients on normal and non-normal directions
Don't teleport with grasping controller (VR)
Tune VR grasping a bit.
This commit is contained in:
erwincoumans 2016-09-12 19:10:20 +01:00
parent af7c44d360
commit e5a8eb2425
8 changed files with 36 additions and 20 deletions

View File

@ -2,9 +2,9 @@
rem premake4 --with-pe vs2010 rem premake4 --with-pe vs2010
rem premake4 --bullet2demos vs2010 rem premake4 --bullet2demos vs2010
cd build3 cd build3
rem premake4 --enable_openvr --targetdir="../bin" vs2010 premake4 --enable_openvr --targetdir="../bin" vs2010
premake4 --enable_pybullet --python_include_dir="c:/python34/include" --python_lib_dir="c:/python34/libs" --enable_openvr --targetdir="../bin" vs2010 rem premake4 --enable_pybullet --python_include_dir="C:/Python-3.6.0a3/include" --python_lib_dir="C:/Python-3.6.0a3/libs" --enable_openvr --targetdir="../bin" vs2010
rem premake4 --enable_openvr --enable_pybullet --targetdir="../bin" vs2010 rem premake4 --enable_openvr --enable_pybullet --targetdir="../bin" vs2010
rem premake4 --targetdir="../server2bin" vs2010 rem premake4 --targetdir="../server2bin" vs2010
rem cd vs2010 rem cd vs2010

View File

@ -3,9 +3,8 @@
<link name="baseLink"> <link name="baseLink">
<contact> <contact>
<lateral_friction value="1.0"/> <lateral_friction value="1.0"/>
<rolling_friction value="0.01"/> <rolling_friction value="0.1"/>
<inertia_scaling value="3.0"/> <inertia_scaling value="3.0"/>
</contact> </contact>
<inertial> <inertial>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>

View File

@ -31,6 +31,9 @@
</joint> </joint>
<link name="left_gripper"> <link name="left_gripper">
<contact>
<lateral_friction value="50.0"/>
</contact>
<visual> <visual>
<origin rpy="0.0 0 0" xyz="0 0 0"/> <origin rpy="0.0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
@ -55,6 +58,9 @@
</joint> </joint>
<link name="left_tip"> <link name="left_tip">
<contact>
<lateral_friction value="50.0"/>
</contact>
<visual> <visual>
<origin rpy="0.0 0 0" xyz="0.09137 0.00495 0"/> <origin rpy="0.0 0 0" xyz="0.09137 0.00495 0"/>
<geometry> <geometry>
@ -63,9 +69,9 @@
</visual> </visual>
<collision> <collision>
<geometry> <geometry>
<mesh filename="l_finger_tip.stl"/> <box size=".03 .03 .02"/>
</geometry> </geometry>
<origin rpy="0.0 0 0" xyz="0.09137 0.00495 0"/> <origin rpy="0.0 0 0" xyz="0.109137 0.00495 0"/>
</collision> </collision>
<inertial> <inertial>
<mass value="0.05"/> <mass value="0.05"/>
@ -82,6 +88,9 @@
</joint> </joint>
<link name="right_gripper"> <link name="right_gripper">
<contact>
<lateral_friction value="50.0"/>
</contact>
<visual> <visual>
<origin rpy="-3.1415 0 0" xyz="0 0 0"/> <origin rpy="-3.1415 0 0" xyz="0 0 0"/>
<geometry> <geometry>
@ -106,6 +115,9 @@
</joint> </joint>
<link name="right_tip"> <link name="right_tip">
<contact>
<lateral_friction value="50.0"/>
</contact>
<visual> <visual>
<origin rpy="-3.1415 0 0" xyz="0.09137 0.00495 0"/> <origin rpy="-3.1415 0 0" xyz="0.09137 0.00495 0"/>
<geometry> <geometry>
@ -114,9 +126,9 @@
</visual> </visual>
<collision> <collision>
<geometry> <geometry>
<mesh filename="l_finger_tip.stl"/> <box size=".03 .03 .02"/>
</geometry> </geometry>
<origin rpy="-3.1415 0 0" xyz="0.09137 0.00495 0"/> <origin rpy="-3.1415 0 0" xyz="0.109137 0.00495 0"/>
</collision> </collision>
<inertial> <inertial>
<mass value="0.05"/> <mass value="0.05"/>

View File

@ -525,7 +525,7 @@ PhysicsServerCommandProcessor::PhysicsServerCommandProcessor()
m_data = new PhysicsServerCommandProcessorInternalData(); m_data = new PhysicsServerCommandProcessorInternalData();
createEmptyDynamicsWorld(); createEmptyDynamicsWorld();
m_data->m_dynamicsWorld->getSolverInfo().m_linearSlop = 0.0001; m_data->m_dynamicsWorld->getSolverInfo().m_linearSlop = 0.0;
} }
@ -2823,7 +2823,7 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
m_data->m_gripperMultiBody->setJointPos(0, SIMD_HALF_PI); m_data->m_gripperMultiBody->setJointPos(0, SIMD_HALF_PI);
m_data->m_gripperMultiBody->setJointPos(2, SIMD_HALF_PI); m_data->m_gripperMultiBody->setJointPos(2, SIMD_HALF_PI);
} }
m_data->m_gripperRigidbodyFixed->setMaxAppliedImpulse(2.); m_data->m_gripperRigidbodyFixed->setMaxAppliedImpulse(1.);
btMultiBodyDynamicsWorld* world = (btMultiBodyDynamicsWorld*)m_data->m_dynamicsWorld; btMultiBodyDynamicsWorld* world = (btMultiBodyDynamicsWorld*)m_data->m_dynamicsWorld;
world->addMultiBodyConstraint(m_data->m_gripperRigidbodyFixed); world->addMultiBodyConstraint(m_data->m_gripperRigidbodyFixed);
} }
@ -2844,7 +2844,7 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)m_data->m_gripperMultiBody->getLink(i * 2).m_userPtr; btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)m_data->m_gripperMultiBody->getLink(i * 2).m_userPtr;
if (motor) if (motor)
{ {
motor->setErp(0.005); motor->setErp(0.01);
if (gVRGripperClosed) if (gVRGripperClosed)
{ {
@ -2855,7 +2855,7 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
motor->setPositionTarget(SIMD_HALF_PI, 1); motor->setPositionTarget(SIMD_HALF_PI, 1);
} }
motor->setVelocityTarget(0, 0.1); motor->setVelocityTarget(0, 0.1);
btScalar maxImp = 550.*m_data->m_physicsDeltaTime; btScalar maxImp = 1550.*m_data->m_physicsDeltaTime;
motor->setMaxAppliedImpulse(maxImp); motor->setMaxAppliedImpulse(maxImp);
} }
} }

View File

@ -1101,6 +1101,7 @@ class CommonExampleInterface* PhysicsServerCreateFunc(struct CommonExampleOpt
} }
static int gGraspingController = 2;
void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orn[4]) void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orn[4])
{ {
@ -1109,9 +1110,13 @@ void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int butt
if (controllerId<0 || controllerId>=MAX_VR_CONTROLLERS) if (controllerId<0 || controllerId>=MAX_VR_CONTROLLERS)
return; return;
if (button==1 && state==0)
if (controllerId != gGraspingController)
{ {
gVRTeleportPos = gLastPickPos; if (button == 1 && state == 0)
{
gVRTeleportPos = gLastPickPos;
}
} }
if (button==32 && state==0) if (button==32 && state==0)
{ {
@ -1124,7 +1129,7 @@ void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int butt
m_args[0].m_isVrControllerTeleporting[controllerId] = true; m_args[0].m_isVrControllerTeleporting[controllerId] = true;
} }
if (controllerId == 3 && (button == 33)) if (controllerId == gGraspingController && (button == 33))
{ {
gVRGripperClosed =state; gVRGripperClosed =state;
} }
@ -1155,7 +1160,7 @@ void PhysicsServerExample::vrControllerMoveCallback(int controllerId, float pos[
printf("Controller Id exceeds max: %d > %d", controllerId, MAX_VR_CONTROLLERS); printf("Controller Id exceeds max: %d > %d", controllerId, MAX_VR_CONTROLLERS);
return; return;
} }
if (controllerId == 3) if (controllerId == gGraspingController)
{ {
gVRGripperPos.setValue(pos[0] + gVRTeleportPos[0], pos[1] + gVRTeleportPos[1], pos[2] + gVRTeleportPos[2]); gVRGripperPos.setValue(pos[0] + gVRTeleportPos[0], pos[1] + gVRTeleportPos[1], pos[2] + gVRTeleportPos[2]);
btQuaternion orgOrn(orn[0], orn[1], orn[2], orn[3]); btQuaternion orgOrn(orn[0], orn[1], orn[2], orn[3]);

View File

@ -702,7 +702,7 @@ bool CMainApplication::HandleInput()
glPolygonMode( GL_FRONT_AND_BACK, GL_LINE ); glPolygonMode( GL_FRONT_AND_BACK, GL_LINE );
///todo(erwincoumans) can't use reguar debug drawer, because physics/graphics are not in sync ///todo(erwincoumans) can't use reguar debug drawer, because physics/graphics are not in sync
//add a special debug drawer that deals with this //add a special debug drawer that deals with this
//gDebugDrawFlags = btIDebugDraw::DBG_DrawContactPoints //gDebugDrawFlags = btIDebugDraw::DBG_DrawWireframe;// :DBG_DrawContactPoints
//btIDebugDraw::DBG_DrawConstraintLimits+ //btIDebugDraw::DBG_DrawConstraintLimits+
//btIDebugDraw::DBG_DrawConstraints //btIDebugDraw::DBG_DrawConstraints
; ;

View File

@ -27,7 +27,7 @@ ContactAddedCallback gContactAddedCallback=0;
///User can override this material combiner by implementing gContactAddedCallback and setting body0->m_collisionFlags |= btCollisionObject::customMaterialCallback; ///User can override this material combiner by implementing gContactAddedCallback and setting body0->m_collisionFlags |= btCollisionObject::customMaterialCallback;
btScalar btManifoldResult::calculateCombinedRollingFriction(const btCollisionObject* body0,const btCollisionObject* body1) btScalar btManifoldResult::calculateCombinedRollingFriction(const btCollisionObject* body0,const btCollisionObject* body1)
{ {
btScalar friction = body0->getRollingFriction() * body1->getRollingFriction(); btScalar friction = body0->getRollingFriction() * body1->getFriction() + body1->getRollingFriction() * body0->getFriction();
const btScalar MAX_FRICTION = btScalar(10.); const btScalar MAX_FRICTION = btScalar(10.);
if (friction < -MAX_FRICTION) if (friction < -MAX_FRICTION)

View File

@ -1011,8 +1011,8 @@ void btMultiBodyConstraintSolver::convertMultiBodyContact(btPersistentManifold*
if (rollingFriction > 0) if (rollingFriction > 0)
{ {
addMultiBodyRollingFrictionConstraint(cp.m_normalWorldOnB,manifold,frictionIndex,cp,colObj0,colObj1, relaxation,infoGlobal); addMultiBodyRollingFrictionConstraint(cp.m_normalWorldOnB,manifold,frictionIndex,cp,colObj0,colObj1, relaxation,infoGlobal);
addMultiBodyRollingFrictionConstraint(cp.m_lateralFrictionDir1,manifold,frictionIndex,cp,colObj0,colObj1, relaxation,infoGlobal); //addMultiBodyRollingFrictionConstraint(cp.m_lateralFrictionDir1,manifold,frictionIndex,cp,colObj0,colObj1, relaxation,infoGlobal);
addMultiBodyRollingFrictionConstraint(cp.m_lateralFrictionDir2,manifold,frictionIndex,cp,colObj0,colObj1, relaxation,infoGlobal); //addMultiBodyRollingFrictionConstraint(cp.m_lateralFrictionDir2,manifold,frictionIndex,cp,colObj0,colObj1, relaxation,infoGlobal);
rollingFriction--; rollingFriction--;
} }