forked from erwincoumans/pybullet_robots
-
Notifications
You must be signed in to change notification settings - Fork 0
/
baxter_ik_demo.py
195 lines (147 loc) · 5.58 KB
/
baxter_ik_demo.py
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
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
from time import sleep
import pybullet as p
import numpy as np
def setUpWorld(initialSimSteps=100):
"""
Reset the simulation to the beginning and reload all models.
Parameters
----------
initialSimSteps : int
Returns
-------
baxterId : int
endEffectorId : int
"""
p.resetSimulation()
# Load plane
p.loadURDF("plane.urdf", [0, 0, -1], useFixedBase=True)
sleep(0.1)
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
# Load Baxter
baxterId = p.loadURDF("baxter_common/baxter_description/urdf/toms_baxter.urdf", useFixedBase=True)
p.resetBasePositionAndOrientation(baxterId, [0.5, -0.8, 0.0], [0., 0., -1., -1.])
#p.resetBasePositionAndOrientation(baxterId, [0.5, -0.8, 0.0],[0,0,0,1])
#p.resetBasePositionAndOrientation(baxterId, [0, 0, 0], )
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
# Grab relevant joint IDs
endEffectorId = 48 # (left gripper left finger)
# Set gravity
p.setGravity(0., 0., -10.)
# Let the world run for a bit
for _ in range(initialSimSteps):
p.stepSimulation()
return baxterId, endEffectorId
def getJointRanges(bodyId, includeFixed=False):
"""
Parameters
----------
bodyId : int
includeFixed : bool
Returns
-------
lowerLimits : [ float ] * numDofs
upperLimits : [ float ] * numDofs
jointRanges : [ float ] * numDofs
restPoses : [ float ] * numDofs
"""
lowerLimits, upperLimits, jointRanges, restPoses = [], [], [], []
numJoints = p.getNumJoints(bodyId)
for i in range(numJoints):
jointInfo = p.getJointInfo(bodyId, i)
if includeFixed or jointInfo[3] > -1:
ll, ul = jointInfo[8:10]
jr = ul - ll
# For simplicity, assume resting state == initial state
rp = p.getJointState(bodyId, i)[0]
lowerLimits.append(-2)
upperLimits.append(2)
jointRanges.append(2)
restPoses.append(rp)
return lowerLimits, upperLimits, jointRanges, restPoses
def accurateIK(bodyId, endEffectorId, targetPosition, lowerLimits, upperLimits, jointRanges, restPoses,
useNullSpace=False, maxIter=10, threshold=1e-4):
"""
Parameters
----------
bodyId : int
endEffectorId : int
targetPosition : [float, float, float]
lowerLimits : [float]
upperLimits : [float]
jointRanges : [float]
restPoses : [float]
useNullSpace : bool
maxIter : int
threshold : float
Returns
-------
jointPoses : [float] * numDofs
"""
closeEnough = False
iter = 0
dist2 = 1e30
numJoints = p.getNumJoints(baxterId)
while (not closeEnough and iter<maxIter):
if useNullSpace:
jointPoses = p.calculateInverseKinematics(bodyId, endEffectorId, targetPosition,
lowerLimits=lowerLimits, upperLimits=upperLimits, jointRanges=jointRanges,
restPoses=restPoses)
else:
jointPoses = p.calculateInverseKinematics(bodyId, endEffectorId, targetPosition)
for i in range(numJoints):
jointInfo = p.getJointInfo(bodyId, i)
qIndex = jointInfo[3]
if qIndex > -1:
p.resetJointState(bodyId,i,jointPoses[qIndex-7])
ls = p.getLinkState(bodyId,endEffectorId)
newPos = ls[4]
diff = [targetPosition[0]-newPos[0],targetPosition[1]-newPos[1],targetPosition[2]-newPos[2]]
dist2 = np.sqrt((diff[0]*diff[0] + diff[1]*diff[1] + diff[2]*diff[2]))
print("dist2=",dist2)
closeEnough = (dist2 < threshold)
iter=iter+1
print("iter=",iter)
return jointPoses
def setMotors(bodyId, jointPoses):
"""
Parameters
----------
bodyId : int
jointPoses : [float] * numDofs
"""
numJoints = p.getNumJoints(bodyId)
for i in range(numJoints):
jointInfo = p.getJointInfo(bodyId, i)
#print(jointInfo)
qIndex = jointInfo[3]
if qIndex > -1:
p.setJointMotorControl2(bodyIndex=bodyId, jointIndex=i, controlMode=p.POSITION_CONTROL,
targetPosition=jointPoses[qIndex-7])
if __name__ == "__main__":
guiClient = p.connect(p.GUI)
p.resetDebugVisualizerCamera(2., 180, 0., [0.52, 0.2, np.pi/4.])
targetPosXId = p.addUserDebugParameter("targetPosX",-1,1,0.2)
targetPosYId = p.addUserDebugParameter("targetPosY",-1,1,0)
targetPosZId = p.addUserDebugParameter("targetPosZ",-1,1,-0.1)
nullSpaceId = p.addUserDebugParameter("nullSpace",0,1,1)
baxterId, endEffectorId = setUpWorld()
lowerLimits, upperLimits, jointRanges, restPoses = getJointRanges(baxterId, includeFixed=False)
#targetPosition = [0.2, 0.8, -0.1]
#targetPosition = [0.8, 0.2, -0.1]
targetPosition = [0.2, 0.0, -0.1]
p.addUserDebugText("TARGET", targetPosition, textColorRGB=[1,0,0], textSize=1.5)
maxIters = 100000
sleep(1.)
p.getCameraImage(320,200, renderer=p.ER_BULLET_HARDWARE_OPENGL )
for _ in range(maxIters):
p.stepSimulation()
targetPosX = p.readUserDebugParameter(targetPosXId)
targetPosY = p.readUserDebugParameter(targetPosYId)
targetPosZ = p.readUserDebugParameter(targetPosZId)
nullSpace = p.readUserDebugParameter(nullSpaceId)
targetPosition=[targetPosX,targetPosY,targetPosZ]
useNullSpace = nullSpace>0.5
print("useNullSpace=",useNullSpace)
jointPoses = accurateIK(baxterId, endEffectorId, targetPosition, lowerLimits, upperLimits, jointRanges, restPoses, useNullSpace=useNullSpace)
setMotors(baxterId, jointPoses)
#sleep(0.1)