mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-12 21:00:11 +00:00
add implicit plane_implicit.urdf and use it in humanoid_running.py (numpy version)
This commit is contained in:
parent
e961800278
commit
ed890f23e6
35
data/plane_implicit.urdf
Normal file
35
data/plane_implicit.urdf
Normal file
@ -0,0 +1,35 @@
|
|||||||
|
<?xml version="0.0" ?>
|
||||||
|
<robot name="plane">
|
||||||
|
<link name="planeLink">
|
||||||
|
<contact>
|
||||||
|
<!--<friction_anchor/>-->
|
||||||
|
<lateral_friction value="1."/>
|
||||||
|
<rolling_friction value="0.0"/>
|
||||||
|
<stiffness value="30000"/>
|
||||||
|
<damping value="10000"/>
|
||||||
|
</contact>
|
||||||
|
<inertial>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
<mass value=".0"/>
|
||||||
|
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="plane100.obj" scale="1 1 1"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="1 1 1 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
<!--<origin rpy="0 0 0" xyz="0 0 -5"/>-->
|
||||||
|
<geometry>
|
||||||
|
<plane normal="0 0 1"/>
|
||||||
|
<!--<box size="100 100 10"/>-->
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
</robot>
|
||||||
|
|
@ -21,7 +21,7 @@ if (cid<0):
|
|||||||
|
|
||||||
#p.setGravity(1,2,-9.8)
|
#p.setGravity(1,2,-9.8)
|
||||||
#p.setDefaultContactERP (0.4)
|
#p.setDefaultContactERP (0.4)
|
||||||
#p.setGravity(0,0,-9.8)
|
p.setGravity(0,0,-9.8)
|
||||||
#numSubSteps=4 and fixedTimeStep=1.0/60. is an effective internal fixed step of 1./240
|
#numSubSteps=4 and fixedTimeStep=1.0/60. is an effective internal fixed step of 1./240
|
||||||
#recommended to not go below 50 solver iterations
|
#recommended to not go below 50 solver iterations
|
||||||
p.setPhysicsEngineParameter(fixedTimeStep=1.0/60., numSolverIterations=550, numSubSteps=8)
|
p.setPhysicsEngineParameter(fixedTimeStep=1.0/60., numSolverIterations=550, numSubSteps=8)
|
||||||
@ -29,7 +29,7 @@ p.setPhysicsEngineParameter(fixedTimeStep=1.0/60., numSolverIterations=550, numS
|
|||||||
#mp4log = p.startStateLogging(p.STATE_LOGGING_VIDEO_MP4,"humanoid.mp4")
|
#mp4log = p.startStateLogging(p.STATE_LOGGING_VIDEO_MP4,"humanoid.mp4")
|
||||||
|
|
||||||
#p.loadSDF("stadium.sdf")
|
#p.loadSDF("stadium.sdf")
|
||||||
p.loadURDF("plane.urdf")
|
p.loadURDF("plane_implicit.urdf")
|
||||||
|
|
||||||
objs = p.loadMJCF("mjcf/humanoid_symmetric_no_ground.xml",flags = p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS)
|
objs = p.loadMJCF("mjcf/humanoid_symmetric_no_ground.xml",flags = p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS)
|
||||||
human = objs[0]
|
human = objs[0]
|
||||||
|
Loading…
Reference in New Issue
Block a user