@@ -69,6 +69,7 @@ modified (Craig's convention) Denavit-Hartenberg notation
69
69
import roboticstoolbox as rtb
70
70
robot = rtb.models.DH .Panda()
71
71
print (robot)
72
+
72
73
┏━━━━━━━━┳━━━━━━━━┳━━━━━┳━━━━━━━┳━━━━━━━━━┳━━━━━━━━┓
73
74
┃ aⱼ₋₁ ┃ ⍺ⱼ₋₁ ┃ θⱼ ┃ dⱼ ┃ q⁻ ┃ q⁺ ┃
74
75
┣━━━━━━━━╋━━━━━━━━╋━━━━━╋━━━━━━━╋━━━━━━━━━╋━━━━━━━━┫
@@ -94,41 +95,51 @@ print(robot)
94
95
95
96
T = robot.fkine(robot.qz) # forward kinematics
96
97
print (T)
98
+
97
99
0.707107 0.707107 0 0.088
98
100
0.707107 - 0.707107 0 0
99
101
0 0 - 1 0.823
100
102
0 0 0 1
101
103
```
104
+ (Python prompts are not shown to make it easy to copy+paste the code)
102
105
103
- We can animate a path
106
+ We can solve inverse kinematics very easily. We first choose an SE(3) pose
107
+ defined in terms of position and orientation (end-effector z-axis down (-Z) and finger
108
+ orientation (+Y)).
104
109
105
110
``` python
106
- >> > qt = rtb.trajectory.jtraj(robot.qz, robot.qr, 50 )
107
- >> > robot.plot(qt.q, movie = ' panda1.gif' )
108
- ```
111
+ from spatialmath import SE3
109
112
110
- ![ Panda trajectory animation] ( https://github.com/petercorke/robotics-toolbox-python/raw/master/docs/figs/panda1.gif )
113
+ T = SE3(0.8 , 0.2 , 0.1 ) * SE3 .OA([0 , 1 , 0 ], [0 , 0 , - 1 ])
114
+ q_pickup, * _ = robot.ikine(T) # solve IK, ignore additional outputs
115
+ print (q_pickup) # display joint angles
111
116
112
- which uses the default matplotlib backend.
117
+ [ 1.10903519 1.21806211 0.10114796 1.49547496 0.33270093 - 0.29437262 - 0.8927488 ]
113
118
114
- Inverse kinematics is straightforward
119
+ print (robot.fkine(q_pickup)) # FK shows that desired end-effector pose was achieved
115
120
116
- ``` python
117
- from spatialmath import SE3
118
- T = SE3(0.1 , 0.2 , 0.5 ) * SE3 .OA([0 , 1 , 0 ], [0 , 0 , - 1 ]) # hand down, fingers || y-axis
119
- q, * _ = robot.ikunc(T) # use optimization-based IK, ignore additional output
120
- print (q) # display joint angles
121
- [ 1.10903519 1.21806211 0.10114796 1.49547496 0.33270093 - 0.29437262 - 0.8927488 ]
122
- print (robot.fkine(q)) # FK shows that desired pose was achieved
123
121
- 1 - 1.31387e-11 - 1.57726e-09 0.0999999
124
122
- 1.31386e-11 1 - 7.46658e-08 0.2
125
123
1.57726e-09 - 7.46658e-08 - 1 0.5
126
- 0 0 0 1
124
+ 0 0 0 1
127
125
```
128
126
127
+ Note that because this robot is redundant we don't have any control over the arm configuration apart from end-effector pose, ie. we can't control the elbow height.
128
+
129
+ We can animate a path from the upright ` qz ` configuration to this pickup configuration
130
+
131
+ ``` python
132
+ qt = rtb.trajectory.jtraj(robot.qz, q_pickup, 50 )
133
+ robot.plot(qt.q, movie = ' panda1.gif' )
134
+ ```
135
+
136
+ ![ Panda trajectory animation] ( https://github.com/petercorke/robotics-toolbox-python/raw/master/docs/figs/panda1.gif )
137
+
138
+ which uses the default matplotlib backend.
139
+
129
140
Let's now load a URDF model of the same robotWe can instantiate our robot inside
130
141
the 3d simulation environment. The kinematic representation is no longer
131
- based in Denavit-Hartenberg parameters, it is now a rigid-body tree.
142
+ based on Denavit-Hartenberg parameters, it is now a rigid-body tree.
132
143
133
144
``` python
134
145
robot = rtb.models.URDF .Panda() # load URDF version of the Panda
@@ -155,6 +166,7 @@ for qk in qt.q: # for each joint configuration on trajectory
155
166
env.step() # update visualization
156
167
```
157
168
169
+ ![ URDF Panda trajectory animation] ( https://github.com/petercorke/robotics-toolbox-python/raw/master/docs/figs/panda2.gif )
158
170
159
171
# Getting going
160
172
0 commit comments