fix rotational friction between btMultiBody and btRigidBody
This commit is contained in:
15
examples/pybullet/examples/rotationalFriction.py
Normal file
15
examples/pybullet/examples/rotationalFriction.py
Normal file
@@ -0,0 +1,15 @@
|
||||
import time
|
||||
import pybullet as p
|
||||
import pybullet_data as pd
|
||||
useMaximalCoordinatesA = True
|
||||
useMaximalCoordinatesB = True
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pd.getDataPath())
|
||||
cube=p.loadURDF("cube_rotate.urdf",useMaximalCoordinates=useMaximalCoordinatesA)
|
||||
p.loadURDF("sphere2.urdf",[0,0,2],useMaximalCoordinates=useMaximalCoordinatesB)
|
||||
p.setGravity(0,0,-10)
|
||||
p.setJointMotorControl2(cube,0,p.VELOCITY_CONTROL,targetVelocity=1, force=100)
|
||||
while (1):
|
||||
p.stepSimulation()
|
||||
time.sleep(1./240.)
|
||||
|
||||
41
examples/pybullet/gym/pybullet_data/cube_rotate.urdf
Normal file
41
examples/pybullet/gym/pybullet_data/cube_rotate.urdf
Normal file
@@ -0,0 +1,41 @@
|
||||
<?xml version="1.0" ?>
|
||||
<robot name="cube">
|
||||
<link name="world"/>
|
||||
|
||||
<link name="baseLink">
|
||||
<contact>
|
||||
<lateral_friction value="1.0"/>
|
||||
<rolling_friction value="0.0"/>
|
||||
<contact_cfm value="0.0"/>
|
||||
<contact_erp value="1.0"/>
|
||||
</contact>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<mass value="1.0"/>
|
||||
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="cube.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"/>
|
||||
<geometry>
|
||||
<box size="1 1 1"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="joint_baseLink_world" type="continuous">
|
||||
<parent link="world"/>
|
||||
<child link="baseLink"/>
|
||||
<dynamics damping="1.0" friction="0.0001"/>
|
||||
<origin xyz="0 0 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
</joint>
|
||||
</robot>
|
||||
|
||||
Reference in New Issue
Block a user