Replies: 4 comments
-
I'm trying out a rear wheel drive racecar simulation and the lateral wheel friction seems to be computed by clipping along each axis instead of the norm. My car snaps to simulation axes when drifting. Here's a minimal example that takes keyboard input. Check it out. import pybullet as p, pybullet_data, time, sys, math
# configure the engine
p.connect(p.GUI, options="--width=1000 --height=800")
p.setAdditionalSearchPath(pybullet_data.getDataPath())
p.resetSimulation()
p.setGravity(0, 0, -10)
p.setPhysicsEngineParameter(enableConeFriction=1) # ensure cone friction
useRealTime = 0
p.setRealTimeSimulation(useRealTime)
# load objects
plane = p.loadURDF("plane.urdf")
car = p.loadURDF("racecar/racecar.urdf")
front_wheels, rear_wheels, steering = [5, 7], [2, 3], [4, 6]
# change friction coefficients
friction_kwargs = {
"lateralFriction": 0.5,
#"rollingFriction": 0,
#"spinningFriction": 0,
}
p.changeDynamics(plane, -1, **friction_kwargs)
for wheel in front_wheels + rear_wheels:
p.changeDynamics(car, wheel, **friction_kwargs)
# run the interactive sim
FPS = 60.0
STRSPD, GASTRQ, BRKTRQ = 5.0, 2e0, 1e0
sign = lambda x: x / abs(x) if x != 0 else 0
t_frame = time.time()
while (True):
# handle user input
keys = p.getKeyboardEvents()
steer, gas, brake = 0.0, 0.0, 0.0
if p.B3G_LEFT_ARROW in keys:
if keys[p.B3G_LEFT_ARROW] == p.KEY_WAS_TRIGGERED: steer += -STRSPD
elif keys[p.B3G_LEFT_ARROW] == p.KEY_IS_DOWN: steer += -STRSPD
if p.B3G_RIGHT_ARROW in keys:
if keys[p.B3G_RIGHT_ARROW] == p.KEY_WAS_TRIGGERED: steer += STRPSD
elif keys[p.B3G_RIGHT_ARROW] == p.KEY_IS_DOWN: steer += STRSPD
if p.B3G_UP_ARROW in keys:
if keys[p.B3G_UP_ARROW] == p.KEY_WAS_TRIGGERED: gas += GASTRQ
elif keys[p.B3G_UP_ARROW] == p.KEY_IS_DOWN: gas += GASTRQ
if p.B3G_DOWN_ARROW in keys:
if keys[p.B3G_DOWN_ARROW] == p.KEY_WAS_TRIGGERED: brake += BRKTRQ
elif keys[p.B3G_DOWN_ARROW] == p.KEY_IS_DOWN: brake += BRKTRQ
if ord("q") in keys: break
# accelerate using a rear wheel drive
for wheel in rear_wheels:
p.setJointMotorControl2(car, wheel, p.TORQUE_CONTROL, force=gas)
# brake with all wheels
for wheel in rear_wheels + front_wheels:
p.setJointMotorControl2(car, wheel, p.VELOCITY_CONTROL,
targetVelocity=0, force=brake)
# steer
for joint in steering:
p.setJointMotorControl2(car, joint, p.POSITION_CONTROL,
targetPosition=-sign(steer) * 0.4)
# step the simulation
if useRealTime == 0:
for i in range(round(240.0 / FPS)):
p.stepSimulation()
# adjust the camera
state = p.getLinkState(car, 0)
pos, orient = state[0], p.getEulerFromQuaternion(state[1])[2]
p.resetDebugVisualizerCamera(2, orient / math.pi * 180 - 90, -40, pos)
# keep FPS
delay = 1.0 / FPS - (time.time() - t_frame)
if useRealTime == 0 and delay > 0: time.sleep(delay)
t_frame = time.time() This might be related to #2117 |
Beta Was this translation helpful? Give feedback.
-
Thanks for pointing this out! Seems like the fix was patched in a month ago; so I should probably just wait for new release or clone and install locally? I'll post if this patch fixes this issue. |
Beta Was this translation helpful? Give feedback.
-
I just built master and the issue is still there. |
Beta Was this translation helpful? Give feedback.
-
I encountered a similar issue when applying external force to a grasped object. I simulated the exact same setting except for implicit cone or pyramid cone friction, and somehow the object can slip with default implicit cone but not with pyramid cone. This does not make sense to me since I assume pyramid cone is always smaller. And object can slip in a very weird trajectory. |
Beta Was this translation helpful? Give feedback.
Uh oh!
There was an error while loading. Please reload this page.
Uh oh!
There was an error while loading. Please reload this page.
-
Friction between surfaces seem to depend on their relative orientation. My experiment is to apply the same external force (in link frame) to a block and look at the change in position and yaw of the block in link frame as it yaws with respect to the floor.


In reality this plot should be uniform. I'm not sure how friction works in bullet - is there some issue with alignment of particles? The periodicity in the dynamics where we get the least dyaw every 45 degrees makes me suspect something like this is happening. If so, how can I resolve this?
Reproducible code (depends on numpy)
URDF to be saved as "block_big.urdf" in the same directory:
(posted to pybullet forums, but maybe I'll get more luck here)
Beta Was this translation helpful? Give feedback.
All reactions