mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-13 05:10:08 +00:00
tune gripper parameters for VR demo
This commit is contained in:
parent
db3122233f
commit
a3aa8ef7f1
BIN
data/l_finger_collision.stl
Normal file
BIN
data/l_finger_collision.stl
Normal file
Binary file not shown.
@ -17,7 +17,7 @@
|
||||
<origin rpy="0 1.57075 0 " xyz="0.1 0 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="100"/>
|
||||
<mass value="0.5"/>
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
</inertial>
|
||||
</link>
|
||||
@ -32,7 +32,7 @@
|
||||
|
||||
<link name="left_gripper">
|
||||
<contact>
|
||||
<lateral_friction value="50.0"/>
|
||||
<lateral_friction value="5.0"/>
|
||||
<spinning_friction value="0.1"/>
|
||||
</contact>
|
||||
<visual>
|
||||
@ -41,8 +41,14 @@
|
||||
<mesh filename="l_finger.stl"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="l_finger_collision.stl" scale=".9 .9 .9"/>
|
||||
</geometry>
|
||||
<origin rpy="0.0 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.05"/>
|
||||
<mass value="0.5"/>
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
</inertial>
|
||||
</link>
|
||||
@ -54,7 +60,7 @@
|
||||
|
||||
<link name="left_tip">
|
||||
<contact>
|
||||
<lateral_friction value="50.0"/>
|
||||
<lateral_friction value="5.0"/>
|
||||
<spinning_friction value="0.1"/>
|
||||
</contact>
|
||||
<visual>
|
||||
@ -65,12 +71,12 @@
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size=".13 .03 .02"/>
|
||||
<box size=".03 .03 .02"/>
|
||||
</geometry>
|
||||
<origin rpy="0.0 0 0" xyz="0.055 0.00495 0"/>
|
||||
<origin rpy="0.0 0 0" xyz="0.105 0.00495 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.05"/>
|
||||
<mass value="0.1"/>
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
</inertial>
|
||||
</link>
|
||||
@ -85,8 +91,8 @@
|
||||
|
||||
<link name="right_gripper">
|
||||
<contact>
|
||||
<lateral_friction value="50.0"/>
|
||||
<spinning_friction value="0.1"/>
|
||||
<lateral_friction value="5.0"/>
|
||||
<spinning_friction value="0.3"/>
|
||||
</contact>
|
||||
<visual>
|
||||
<origin rpy="-3.1415 0 0" xyz="0 0 0"/>
|
||||
@ -94,6 +100,12 @@
|
||||
<mesh filename="l_finger.stl"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="l_finger_collision.stl" scale=".9 .9 .9"/>
|
||||
</geometry>
|
||||
<origin rpy="-3.1415 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.05"/>
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
@ -107,8 +119,8 @@
|
||||
|
||||
<link name="right_tip">
|
||||
<contact>
|
||||
<lateral_friction value="50.0"/>
|
||||
<spinning_friction value="0.1"/>
|
||||
<lateral_friction value="5.0"/>
|
||||
<spinning_friction value=".2"/>
|
||||
</contact>
|
||||
<visual>
|
||||
<origin rpy="-3.1415 0 0" xyz="0.09137 0.00495 0"/>
|
||||
@ -118,9 +130,9 @@
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size=".13 .03 .02"/>
|
||||
<box size=".03 .03 .02"/>
|
||||
</geometry>
|
||||
<origin rpy="-3.1415 0 0" xyz="0.055 0.00495 0"/>
|
||||
<origin rpy="-3.1415 0 0" xyz="0.105 0.00495 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.05"/>
|
||||
|
@ -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);
|
||||
}
|
||||
}
|
||||
|
@ -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);
|
||||
|
Loading…
Reference in New Issue
Block a user