mirror of
https://github.com/bulletphysics/bullet3
synced 2025-01-19 05:20:06 +00:00
disable cone friction in example
This commit is contained in:
parent
10020baa71
commit
21bc93a084
@ -10,7 +10,12 @@ clid = p.connect(p.SHARED_MEMORY)
|
||||
|
||||
if (clid < 0):
|
||||
p.connect(p.GUI)
|
||||
|
||||
p.setPhysicsEngineParameter(enableConeFriction=0)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
|
||||
|
||||
p.loadURDF("plane.urdf", [0, 0, -0.3])
|
||||
husky = p.loadURDF("husky/husky.urdf", [0.290388, 0.329902, -0.310270],
|
||||
[0.002328, -0.000984, 0.996491, 0.083659])
|
||||
@ -62,7 +67,7 @@ useNullSpace = 0
|
||||
useOrientation = 0
|
||||
#If we set useSimulation=0, it sets the arm pose to be the IK result directly without using dynamic control.
|
||||
#This can be used to test the IK result accuracy.
|
||||
useSimulation = 0
|
||||
useSimulation = 1
|
||||
useRealTimeSimulation = 1
|
||||
p.setRealTimeSimulation(useRealTimeSimulation)
|
||||
#trailDuration is duration (in seconds) after debug lines will be removed automatically
|
||||
|
Loading…
Reference in New Issue
Block a user