summaryrefslogtreecommitdiff
path: root/examples/pybullet/examples/forcetorquesensor.py
blob: 9e0f343a350601ab636c8116cd27c8c9fff2499c (plain)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
import pybullet as p
p.connect(p.DIRECT)
hinge = p.loadURDF("hinge.urdf")
print("mass of linkA = 1kg, linkB = 1kg, total mass = 2kg")

hingeJointIndex = 0

#by default, joint motors are enabled, maintaining zero velocity
p.setJointMotorControl2(hinge,hingeJointIndex,p.VELOCITY_CONTROL,0,0,0)

p.setGravity(0,0,-10)
p.stepSimulation()
print("joint state without sensor")

print(p.getJointState(0,0))
p.enableJointForceTorqueSensor(hinge,hingeJointIndex)
p.stepSimulation()
print("joint state with force/torque sensor, gravity [0,0,-10]")
print(p.getJointState(0,0))
p.setGravity(0,0,0)
p.stepSimulation()
print("joint state with force/torque sensor, no gravity")
print(p.getJointState(0,0))

p.disconnect()