15
15
16
16
# Create a Panda robot object
17
17
r = rtb .models .Frankie ()
18
+ panda = rtb .models .Panda ()
18
19
19
20
# Set joint angles to ready configuration
20
21
r .q = r .qr
21
22
23
+ b1 = rtb .Box (
24
+ scale = [0.60 , 1.1 , 0.02 ],
25
+ base = sm .SE3 (1.95 , 0 , 0.20 ))
26
+
27
+ b2 = rtb .Box (
28
+ scale = [0.60 , 1.1 , 0.02 ],
29
+ base = sm .SE3 (1.95 , 0 , 0.60 ))
30
+
31
+ b3 = rtb .Box (
32
+ scale = [0.60 , 1.1 , 0.02 ],
33
+ base = sm .SE3 (1.95 , 0 , 1.00 ))
34
+
35
+ b4 = rtb .Box (
36
+ scale = [0.60 , 1.1 , 0.02 ],
37
+ base = sm .SE3 (1.95 , 0 , 1.40 ))
38
+
39
+ b5 = rtb .Box (
40
+ scale = [0.60 , 0.02 , 1.40 ],
41
+ base = sm .SE3 (1.95 , 0.55 , 0.7 ))
42
+
43
+ b6 = rtb .Box (
44
+ scale = [0.60 , 0.02 , 1.40 ],
45
+ base = sm .SE3 (1.95 , - 0.55 , 0.7 ))
46
+
47
+ # Make two obstacles with velocities
48
+ s0 = rtb .Sphere (
49
+ radius = 0.05 ,
50
+ base = sm .SE3 (1.52 , 0.4 , 0.4 )
51
+ )
52
+ # s0.v = [0, -0.2, 0, 0, 0, 0]
53
+
54
+ s1 = rtb .Sphere (
55
+ radius = 0.05 ,
56
+ base = sm .SE3 (0.5 , 0.45 , 0.85 )
57
+ )
58
+ s1 .v = [0 , - 0.2 , 0 , 0 , 0 , 0 ]
59
+
60
+ # s2 = rtb.Box(
61
+ # scale=[0.1, 3.0, 1.0],
62
+ # base=sm.SE3(1.0, 0.0, 1.5) * sm.SE3.Ry(-np.pi/3)
63
+ # )
64
+
65
+ s2 = rtb .Sphere (
66
+ radius = 0.2 ,
67
+ base = sm .SE3 (1.0 , - 0.3 , 0.4 )
68
+ )
69
+
70
+ # s3 = rtb.Box(
71
+ # scale=[2.0, 0.1, 2.0],
72
+ # base=sm.SE3(0.0, 0.5, 0.0)
73
+ # )
74
+
75
+ # s4 = rtb.Box(
76
+ # scale=[2.0, 0.1, 2.0],
77
+ # base=sm.SE3(0.0, -0.5, 0.0)
78
+ # )
79
+
80
+ collisions = [s0 , s1 , s2 ]
81
+
82
+ # Make a target
83
+ target = rtb .Sphere (
84
+ radius = 0.02 ,
85
+ base = sm .SE3 (1.3 , - 0.2 , 0.0 )
86
+ )
87
+
22
88
# Add the puma to the simulator
23
89
env .add (r )
90
+ env .add (s0 )
91
+ env .add (s1 )
92
+ env .add (s2 )
93
+ # env.add(s3)
94
+ # env.add(s4)
95
+ env .add (b1 )
96
+ env .add (b2 )
97
+ env .add (b3 )
98
+ env .add (b4 )
99
+ env .add (b5 )
100
+ env .add (b6 )
101
+ env .add (target )
102
+
103
+
104
+
24
105
time .sleep (1 )
25
106
26
- Tep = r .fkine (r .q ) * sm .SE3 .Tx (1.0 ) * sm .SE3 .Ty (1.0 )
107
+ Tep = r .fkine (r .q ) * sm .SE3 .Tx (1.3 ) * sm .SE3 .Ty (0.4 ) * sm .SE3 .Tz (- 0.2 )
108
+ target .base = Tep
27
109
28
110
arrived = False
29
111
30
- dt = 0.05
112
+ dt = 0.01
113
+
114
+ # env.start_recording('frankie_recording', 1 / dt)
31
115
32
116
while not arrived :
33
- v , arrived = rtb .p_servo (r .fkine (r .q ), Tep , 0.1 )
34
- r .qd = np .linalg .pinv (r .jacobe (r .q )) @ v
117
+
118
+ # The pose of the Panda's end-effector
119
+ Te = r .fkine (r .q )
120
+
121
+ # Transform from the end-effector to desired pose
122
+ eTep = Te .inv () * Tep
123
+
124
+ # Spatial error
125
+ e = np .sum (np .abs (np .r_ [eTep .t , eTep .rpy () * np .pi / 180 ]))
126
+
127
+ v , arrived = rtb .p_servo (r .fkine (r .q ), Tep , gain = 0.6 , threshold = 0.01 )
128
+
129
+ # Gain term (lambda) for control minimisation
130
+ Y = 0.01
131
+
132
+ # Quadratic component of objective function
133
+ Q = np .eye (r .n + 6 )
134
+
135
+ # Joint velocity component of Q
136
+ Q [:r .n , :r .n ] *= Y
137
+
138
+ # Slack component of Q
139
+ Q [r .n :, r .n :] = (1 / e ) * np .eye (6 )
140
+ # Q[r.n:, r.n:] = 10000 * np.eye(6)
141
+
142
+ # The equality contraints
143
+ Aeq = np .c_ [r .jacobe (r .q ), np .eye (6 )]
144
+ beq = v .reshape ((6 ,))
145
+
146
+ # The inequality constraints for joint limit avoidance
147
+ Ain = np .zeros ((r .n + 6 , r .n + 6 ))
148
+ bin = np .zeros (r .n + 6 )
149
+
150
+ # The minimum angle (in radians) in which the joint is allowed to approach
151
+ # to its limit
152
+ ps = 0.05
153
+
154
+ # The influence angle (in radians) in which the velocity damper
155
+ # becomes active
156
+ pi = 0.9
157
+
158
+ # Form the joint limit velocity damper
159
+ Ain [:r .n , :r .n ], bin [:r .n ] = r .joint_velocity_damper (ps , pi , r .n )
160
+
161
+ # For each collision in the scene
162
+ for collision in collisions :
163
+
164
+ # Form the velocity damper inequality contraint for each collision
165
+ # object on the robot to the collision in the scene
166
+ c_Ain , c_bin = r .link_collision_damper (
167
+ collision , r .q [:r .n ], 0.3 , 0.01 , xi = 1.0 ,
168
+ startlink = r .link_dict ['panda_base0' ],
169
+ endlink = r .link_dict ['frankie_hand' ])
170
+
171
+ # If there are any parts of the robot within the influence distance
172
+ # to the collision in the scene
173
+ if c_Ain is not None and c_bin is not None :
174
+ c_Ain = np .c_ [c_Ain , np .zeros ((c_Ain .shape [0 ], 6 ))]
175
+
176
+ # Stack the inequality constraints
177
+ Ain = np .r_ [Ain , c_Ain ]
178
+ bin = np .r_ [bin , c_bin ]
179
+
180
+ # Linear component of objective function: the manipulability Jacobian
181
+ Jm = r .jacobm (r .q ).reshape ((r .n ,))
182
+ Jm [1 ] = 0
183
+ Jm [2 :] = panda .jacobm (r .q [2 :]).reshape ((7 ,))
184
+ # print(Jm)
185
+ # Jm = np.zeros(9)
186
+ c = np .r_ [- Jm , np .zeros (6 )]
187
+
188
+ # The lower and upper bounds on the joint velocity and slack variable
189
+ lb = - np .r_ [r .qdlim [:r .n ], 10 * np .ones (6 )]
190
+ ub = np .r_ [r .qdlim [:r .n ], 10 * np .ones (6 )]
191
+
192
+ # Solve for the joint velocities dq
193
+ qd = qp .solve_qp (Q , c , Ain , bin , Aeq , beq , lb = lb , ub = ub )
194
+
195
+ # Apply the joint velocities to the Panda
196
+ r .qd [:r .n ] = qd [:r .n ]
197
+
198
+ # Step the simulator by 50 ms
35
199
env .step (dt )
200
+
201
+ # env.stop_recording()
0 commit comments