2 GTSAM Copyright 2010-2018, Georgia Tech Research Corporation,
3 Atlanta, Georgia 30332-0415
5 Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 See LICENSE for the license information
9 Kinematics of three-link manipulator with GTSAM poses and product of exponential maps.
10 Author: Frank Dellaert
14 from __future__
import print_function
18 from functools
import reduce
20 import matplotlib.pyplot
as plt
22 from mpl_toolkits.mplot3d
import Axes3D
26 from gtsam
import Pose2
31 """Create 3D double numpy array."""
32 return np.array([x, y, z], dtype=float)
36 """Compose all Pose2 transforms given as arguments from left to right."""
37 return reduce((
lambda x, y: x.compose(y)), poses)
41 """Pose2 vee operator."""
42 return vector3(M[0, 2], M[1, 2], M[1, 0])
46 """Difference between x,y,,theta components of SE(2) poses."""
47 return vector3(g1.x() - g0.x(), g1.y() - g0.y(), g1.theta() - g0.theta())
51 """ Create an interpolated trajectory in SE(2), treating x,y, and theta separately.
52 g0 and g1 are the initial and final pose, respectively.
53 N is the number of *intervals*
57 return [
Pose2(g0.x()+e[0]*t, g0.y()+e[1]*t, g0.theta()+e[2]*t)
for t
in np.linspace(0, 1, N)]
61 """Three-link arm class."""
73 """ Forward kinematics.
74 Takes numpy array of joint angles, in radians.
76 sXl1 =
Pose2(0, 0, math.radians(90))
77 l1Zl1 =
Pose2(0, 0, q[0])
79 l2Zl2 =
Pose2(0, 0, q[1])
81 l3Zl3 =
Pose2(0, 0, q[2])
83 return compose(sXl1, l1Zl1, l1Xl2, l2Zl2, l2Xl3, l3Zl3, l3Xt)
86 """ Calculate manipulator Jacobian.
87 Takes numpy array of joint angles, in radians.
91 return np.array([[-self.
L1*math.cos(q[0]) - self.
L2*math.cos(a)-self.
L3*math.cos(b),
92 -self.
L1*math.cos(a)-self.
L3*math.cos(b),
93 - self.
L3*math.cos(b)],
94 [-self.
L1*math.sin(q[0]) - self.
L2*math.sin(a)-self.
L3*math.sin(b),
95 -self.
L1*math.sin(a)-self.
L3*math.sin(b),
96 - self.
L3*math.sin(b)],
100 """ Forward kinematics.
101 Takes numpy array of joint angles, in radians.
103 l1Zl1 = Pose2.Expmap(self.
xi1 * q[0])
104 l2Zl2 = Pose2.Expmap(self.
xi2 * q[1])
105 l3Zl3 = Pose2.Expmap(self.
xi3 * q[2])
109 """ Forward kinematics, conjugation form.
110 Takes numpy array of joint angles, in radians.
112 def expmap(x, y, theta):
113 """Implement exponential map via conjugation with axis (x,y)."""
116 l1Zl1 = expmap(0.0, 0.0, q[0])
117 l2Zl2 = expmap(0.0, self.
L1, q[1])
118 l3Zl3 = expmap(0.0, self.
L1+self.
L2, q[2])
121 def ik(self, sTt_desired, e=1e-9):
122 """ Inverse kinematics.
123 Takes desired Pose2 of tool T with respect to base S.
124 Optional: mu, gradient descent rate; e: error norm threshold
126 q = np.radians(
vector3(30, -30, 45))
129 while np.linalg.norm(error) > e:
130 error =
delta(sTt_desired, self.
fk(q))
132 q -= np.dot(np.linalg.pinv(J), error)
135 return np.remainder(q+math.pi, 2*math.pi)-math.pi
138 """ Calculate manipulator Jacobian.
139 Takes numpy array of joint angles, in radians.
140 Returns the manipulator Jacobian of differential twists. When multiplied with
141 a vector of joint velocities, will yield a single differential twist which is
142 the spatial velocity d(sTt)/dt * inv(sTt) of the end-effector pose.
143 Just like always, differential twists can be hatted and multiplied with spatial
144 coordinates of a point to give the spatial velocity of the point.
146 l1Zl1 = Pose2.Expmap(self.
xi1 * q[0])
147 l2Zl2 = Pose2.Expmap(self.
xi2 * q[1])
154 p2 = sTl1.Adjoint(self.
xi2)
157 p3 = sTl2.Adjoint(self.
xi3)
159 differential_twists = [p1, p2, p3]
160 return np.stack(differential_twists, axis=1)
164 Takes figure number, and numpy array of joint angles, in radians.
166 fig = plt.figure(fignum)
169 sXl1 =
Pose2(0, 0, math.radians(90))
170 p1 = sXl1.translation()
171 gtsam_plot.plot_pose2_on_axes(axes, sXl1)
173 def plot_line(p, g, color):
175 line = np.append(p[np.newaxis], q[np.newaxis], axis=0)
176 axes.plot(line[:, 0], line[:, 1], color)
179 l1Zl1 =
Pose2(0, 0, q[0])
181 sTl2 =
compose(sXl1, l1Zl1, l1Xl2)
182 p2 = plot_line(p1, sTl2,
'r-')
183 gtsam_plot.plot_pose2_on_axes(axes, sTl2)
185 l2Zl2 =
Pose2(0, 0, q[1])
187 sTl3 =
compose(sTl2, l2Zl2, l2Xl3)
188 p3 = plot_line(p2, sTl3,
'g-')
189 gtsam_plot.plot_pose2_on_axes(axes, sTl3)
191 l3Zl3 =
Pose2(0, 0, q[2])
193 sTt =
compose(sTl3, l3Zl3, l3Xt)
194 plot_line(p3, sTt,
'b-')
195 gtsam_plot.plot_pose2_on_axes(axes, sTt)
205 """Unit tests for functions used below."""
211 """Helper function that prints out actual and expected if not equal."""
212 equal = actual.equals(expected, tol)
214 raise self.failureException(
215 "Poses are not equal:\n{}!={}".
format(actual, expected))
218 """Make sure forward kinematics is correct for some known test configurations."""
220 expected =
Pose2(0, 2*3.5 + 2.5, math.radians(90))
221 sTt = self.
arm.fk(Q0)
222 self.assertIsInstance(sTt, Pose2)
226 expected =
Pose2(5.78, 1.52, math.radians(-75))
227 sTt = self.
arm.fk(Q1)
231 """Test Jacobian calculation."""
233 expected = np.array([[-9.5, -6, -2.5], [0, 0, 0], [1, 1, 1]], float)
234 J = self.
arm.jacobian(Q0)
235 np.testing.assert_array_almost_equal(J, expected)
238 expected = np.array([[-6, -6, -2.5], [3.5, 0, 0], [1, 1, 1]], float)
239 J = self.
arm.jacobian(Q2)
240 np.testing.assert_array_almost_equal(J, expected)
243 """Make sure POE is correct for some known test configurations."""
245 expected =
Pose2(0, 2*3.5 + 2.5, math.radians(90))
246 sTt = self.
arm.con(Q0)
247 self.assertIsInstance(sTt, Pose2)
251 expected =
Pose2(5.78, 1.52, math.radians(-75))
252 sTt = self.
arm.con(Q1)
256 """Make sure POE is correct for some known test configurations."""
258 expected =
Pose2(0, 2*3.5 + 2.5, math.radians(90))
259 sTt = self.
arm.poe(Q0)
260 self.assertIsInstance(sTt, Pose2)
264 expected =
Pose2(5.78, 1.52, math.radians(-75))
265 sTt = self.
arm.poe(Q1)
269 """Check iterative inverse kinematics function."""
271 actual = self.
arm.ik(
Pose2(0, 2*3.5 + 2.5, math.radians(90)))
272 np.testing.assert_array_almost_equal(actual, Q0, decimal=2)
275 sTt_desired =
Pose2(5.78, 1.52, math.radians(-75))
276 actual = self.
arm.ik(sTt_desired)
278 np.testing.assert_array_almost_equal(actual, Q1, decimal=2)
281 """Test Jacobian calculation."""
283 expected = np.array([[0, 3.5, 7], [0, 0, 0], [1, 1, 1]], float)
284 J = self.
arm.manipulator_jacobian(Q0)
285 np.testing.assert_array_almost_equal(J, expected)
289 [[0, 0, 3.5], [0, -3.5, -3.5], [1, 1, 1]], float)
290 J = self.
arm.manipulator_jacobian(Q2)
291 np.testing.assert_array_almost_equal(J, expected)
295 """ Use trajectory interpolation and then trajectory tracking a la Murray
296 to move a 3-link arm on a straight line.
302 q = np.radians(
vector3(30, -30, 45))
303 sTt_initial = arm.fk(q)
306 sTt_goal =
Pose2(2.4, 4.3, math.radians(0))
311 fig = plt.figure(fignum)
315 gtsam_plot.plot_pose2(fignum, arm.fk(q))
321 error =
delta(sTt, pose)
323 q += np.dot(np.linalg.inv(J), error)
330 if __name__ ==
"__main__":