Files
bullet3/examples/pybullet/examples/motorMaxVelocity.py
erwincoumans ab843b26f0 expose a maximum velocity due to the joint motor in position control.
see also pybullet/examples/motorMaxVelocity.py
this fixes issue 1444
2017-11-21 17:05:28 -08:00

12 lines
396 B
Python

import pybullet as p
import time
p.connect(p.GUI)
cartpole=p.loadURDF("cartpole.urdf")
p.setRealTimeSimulation(1)
p.setJointMotorControl2(cartpole,1,p.POSITION_CONTROL,targetPosition=1000,targetVelocity=0,force=1000, positionGain=1, velocityGain=0, maxVelocity=0.5)
while (1):
p.setGravity(0,0,-10)
js = p.getJointState(cartpole,1)
print("position=",js[0],"velocity=",js[1])
time.sleep(0.01)