Files
bullet3/examples/pybullet/examples/motorMaxVelocity.py
Erwin Coumans ef9570c315 add yapf style and apply yapf to format all Python files
This recreates pull request #2192
2019-04-27 07:31:15 -07:00

21 lines
606 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)