@@ -70,58 +70,58 @@ import roboticstoolbox as rtb
70
70
robot = rtb.models.DH .Panda()
71
71
print (robot)
72
72
73
- ┏━━━━━━━━┳━━━━━━━━┳━━━━━┳━━━━━━━┳━━━━━━━━━┳━━━━━━━━┓
74
- ┃ aⱼ₋₁ ┃ ⍺ⱼ₋₁ ┃ θⱼ ┃ dⱼ ┃ q⁻ ┃ q⁺ ┃
75
- ┣━━━━━━━━╋━━━━━━━━╋━━━━━╋━━━━━━━╋━━━━━━━━━╋━━━━━━━━┫
76
- ┃ 0.0 ┃ 0.0 ° ┃ q1 ┃ 0.333 ┃ - 166.0 ° ┃ 166.0 ° ┃
77
- ┃ 0.0 ┃ - 90.0 ° ┃ q2 ┃ 0.0 ┃ - 101.0 ° ┃ 101.0 ° ┃
78
- ┃ 0.0 ┃ 90.0 ° ┃ q3 ┃ 0.316 ┃ - 166.0 ° ┃ 166.0 ° ┃
79
- ┃ 0.0825 ┃ 90.0 ° ┃ q4 ┃ 0.0 ┃ - 176.0 ° ┃ - 4.0 ° ┃
80
- ┃- 0.0825 ┃ - 90.0 ° ┃ q5 ┃ 0.384 ┃ - 166.0 ° ┃ 166.0 ° ┃
81
- ┃ 0.0 ┃ 90.0 ° ┃ q6 ┃ 0.0 ┃ - 1.0 ° ┃ 215.0 ° ┃
82
- ┃ 0.088 ┃ 90.0 ° ┃ q7 ┃ 0.107 ┃ - 166.0 ° ┃ 166.0 ° ┃
83
- ┗━━━━━━━━┻━━━━━━━━┻━━━━━┻━━━━━━━┻━━━━━━━━━┻━━━━━━━━┛
84
-
85
- ┌─────┬───────────────────────────────────────┐
86
- │tool │ t = 0 , 0 , 0.1 ; rpy/ xyz = - 45 °, 0 °, 0 ° │
87
- └─────┴───────────────────────────────────────┘
88
-
89
- ┌─────┬─────┬────────┬─────┬───────┬─────┬───────┬──────┐
90
- │name │ q0 │ q1 │ q2 │ q3 │ q4 │ q5 │ q6 │
91
- ├─────┼─────┼────────┼─────┼───────┼─────┼───────┼──────┤
92
- │ qz │ 0 ° │ 0 ° │ 0 ° │ 0 ° │ 0 ° │ 0 ° │ 0 ° │
93
- │ qr │ 0 ° │ - 17.2 ° │ 0 ° │ - 126 ° │ 0 ° │ 115 ° │ 45 ° │
94
- └─────┴─────┴────────┴─────┴───────┴─────┴───────┴──────┘
73
+ ┏━━━━━━━━┳━━━━━━━━┳━━━━━┳━━━━━━━┳━━━━━━━━━┳━━━━━━━━┓
74
+ ┃ aⱼ₋₁ ┃ ⍺ⱼ₋₁ ┃ θⱼ ┃ dⱼ ┃ q⁻ ┃ q⁺ ┃
75
+ ┣━━━━━━━━╋━━━━━━━━╋━━━━━╋━━━━━━━╋━━━━━━━━━╋━━━━━━━━┫
76
+ ┃ 0.0 ┃ 0.0 ° ┃ q1 ┃ 0.333 ┃ - 166.0 ° ┃ 166.0 ° ┃
77
+ ┃ 0.0 ┃ - 90.0 ° ┃ q2 ┃ 0.0 ┃ - 101.0 ° ┃ 101.0 ° ┃
78
+ ┃ 0.0 ┃ 90.0 ° ┃ q3 ┃ 0.316 ┃ - 166.0 ° ┃ 166.0 ° ┃
79
+ ┃ 0.0825 ┃ 90.0 ° ┃ q4 ┃ 0.0 ┃ - 176.0 ° ┃ - 4.0 ° ┃
80
+ ┃- 0.0825 ┃ - 90.0 ° ┃ q5 ┃ 0.384 ┃ - 166.0 ° ┃ 166.0 ° ┃
81
+ ┃ 0.0 ┃ 90.0 ° ┃ q6 ┃ 0.0 ┃ - 1.0 ° ┃ 215.0 ° ┃
82
+ ┃ 0.088 ┃ 90.0 ° ┃ q7 ┃ 0.107 ┃ - 166.0 ° ┃ 166.0 ° ┃
83
+ ┗━━━━━━━━┻━━━━━━━━┻━━━━━┻━━━━━━━┻━━━━━━━━━┻━━━━━━━━┛
84
+
85
+ ┌─────┬───────────────────────────────────────┐
86
+ │tool │ t = 0 , 0 , 0.1 ; rpy/ xyz = - 45 °, 0 °, 0 ° │
87
+ └─────┴───────────────────────────────────────┘
88
+
89
+ ┌─────┬─────┬────────┬─────┬───────┬─────┬───────┬──────┐
90
+ │name │ q0 │ q1 │ q2 │ q3 │ q4 │ q5 │ q6 │
91
+ ├─────┼─────┼────────┼─────┼───────┼─────┼───────┼──────┤
92
+ │ qz │ 0 ° │ 0 ° │ 0 ° │ 0 ° │ 0 ° │ 0 ° │ 0 ° │
93
+ │ qr │ 0 ° │ - 17.2 ° │ 0 ° │ - 126 ° │ 0 ° │ 115 ° │ 45 ° │
94
+ └─────┴─────┴────────┴─────┴───────┴─────┴───────┴──────┘
95
95
96
96
T = robot.fkine(robot.qz) # forward kinematics
97
97
print (T)
98
98
99
- 0.707107 0.707107 0 0.088
100
- 0.707107 - 0.707107 0 0
101
- 0 0 - 1 0.823
102
- 0 0 0 1
99
+ 0.707107 0.707107 0 0.088
100
+ 0.707107 - 0.707107 0 0
101
+ 0 0 - 1 0.823
102
+ 0 0 0 1
103
103
```
104
- (Python prompts are not shown to make it easy to copy+paste the code)
104
+ (Python prompts are not shown to make it easy to copy+paste the code, console output is indented )
105
105
106
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)).
107
+ defined in terms of position and orientation (end-effector z-axis down (A= -Z) and finger
108
+ orientation parallel to y-axis (O= +Y)).
109
109
110
110
``` python
111
111
from spatialmath import SE3
112
112
113
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
114
+ q_pickup, * _ = robot.ikunc (T) # solve IK, ignore additional outputs
115
115
print (q_pickup) # display joint angles
116
116
117
- [ 1.10903519 1.21806211 0.10114796 1.49547496 0.33270093 - 0.29437262 - 0.8927488 ]
117
+ [ 1.10903519 1.21806211 0.10114796 1.49547496 0.33270093 - 0.29437262 - 0.8927488 ]
118
118
119
119
print (robot.fkine(q_pickup)) # FK shows that desired end-effector pose was achieved
120
120
121
- - 1 - 1.31387e-11 - 1.57726e-09 0.0999999
122
- - 1.31386e-11 1 - 7.46658e-08 0.2
123
- 1.57726e-09 - 7.46658e-08 - 1 0.5
124
- 0 0 0 1
121
+ - 1 - 1.31387e-11 - 1.57726e-09 0.0999999
122
+ - 1.31386e-11 1 - 7.46658e-08 0.2
123
+ 1.57726e-09 - 7.46658e-08 - 1 0.5
124
+ 0 0 0 1
125
125
```
126
126
127
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.
@@ -135,29 +135,33 @@ robot.plot(qt.q, movie='panda1.gif')
135
135
136
136
![ Panda trajectory animation] ( https://github.com/petercorke/robotics-toolbox-python/raw/master/docs/figs/panda1.gif )
137
137
138
- which uses the default matplotlib backend.
138
+ which uses the default matplotlib backend. Grey arrows show the joint axes and the colored frame shows the end-effector pose.
139
139
140
- Let's now load a URDF model of the same robotWe can instantiate our robot inside
141
- the 3d simulation environment. The kinematic representation is no longer
140
+ Let's now load a URDF model of the same robot. The kinematic representation is no longer
142
141
based on Denavit-Hartenberg parameters, it is now a rigid-body tree.
143
142
144
143
``` python
145
144
robot = rtb.models.URDF .Panda() # load URDF version of the Panda
146
145
print (robot) # display the model
147
146
148
- ┌───┬──────────────┬─────────────┬──────────────┬─────────────────────────────────────────────┐
149
- │id │ link │ parent │ joint │ ETS │
150
- ├───┼──────────────┼─────────────┼──────────────┼───────────────
341A
─────────────────────────────┤
151
- │ 0 │ panda_link0 │ - │ │ │
152
- │ 1 │ panda_link1 │ panda_link0 │ panda_joint1 │ tz(0.333 ) * Rz(q0) │
153
- │ 2 │ panda_link2 │ panda_link1 │ panda_joint2 │ Rx(- 90 °) * Rz(q1) │
154
- │ 3 │ panda_link3 │ panda_link2 │ panda_joint3 │ ty(- 0.316 ) * Rx(90 °) * Rz(q2) │
155
- │ 4 │ panda_link4 │ panda_link3 │ panda_joint4 │ tx(0.0825 ) * Rx(90 °) * Rz(q3) │
156
- │ 5 │ panda_link5 │ panda_link4 │ panda_joint5 │ tx(- 0.0825 ) * ty(0.384 ) * Rx(- 90 °) * Rz(q4) │
157
- │ 6 │ panda_link6 │ panda_link5 │ panda_joint6 │ Rx(90 °) * Rz(q5) │
158
- │ 7 │ panda_link7 │ panda_link6 │ panda_joint7 │ tx(0.088 ) * Rx(90 °) * Rz(q6) │
159
- │ 8 │ @ panda_link8 │ panda_link7 │ panda_joint8 │ tz(0.107 ) │
160
- └───┴──────────────┴─────────────┴──────────────┴─────────────────────────────────────────────┘
147
+ ┌───┬──────────────┬─────────────┬──────────────┬─────────────────────────────────────────────┐
148
+ │id │ link │ parent │ joint │ ETS │
149
+ ├───┼──────────────┼─────────────┼──────────────┼─────────────────────────────────────────────┤
150
+ │ 0 │ panda_link0 │ - │ │ │
151
+ │ 1 │ panda_link1 │ panda_link0 │ panda_joint1 │ tz(0.333 ) * Rz(q0) │
152
+ │ 2 │ panda_link2 │ panda_link1 │ panda_joint2 │ Rx(- 90 °) * Rz(q1) │
153
+ │ 3 │ panda_link3 │ panda_link2 │ panda_joint3 │ ty(- 0.316 ) * Rx(90 °) * Rz(q2) │
154
+ │ 4 │ panda_link4 │ panda_link3 │ panda_joint4 │ tx(0.0825 ) * Rx(90 °) * Rz(q3) │
155
+ │ 5 │ panda_link5 │ panda_link4 │ panda_joint5 │ tx(- 0.0825 ) * ty(0.384 ) * Rx(- 90 °) * Rz(q4) │
156
+ │ 6 │ panda_link6 │ panda_link5 │ panda_joint6 │ Rx(90 °) * Rz(q5) │
157
+ │ 7 │ panda_link7 │ panda_link6 │ panda_joint7 │ tx(0.088 ) * Rx(90 °) * Rz(q6) │
158
+ │ 8 │ @ panda_link8 │ panda_link7 │ panda_joint8 │ tz(0.107 ) │
159
+ └───┴──────────────┴─────────────┴──────────────┴─────────────────────────────────────────────┘
160
+ ```
161
+
162
+ We can instantiate our robot inside a browser-based 3d-simulation environment.
163
+
164
+ ``` python
161
165
env = rtb.backend.Swift() # instantiate 3D browser-based visualizer
162
166
env.launch() # activate it
163
167
env.add(robot) # add robot to the 3D scene
0 commit comments